From 3bb83ff288bb74a9180b940e0233083bc2a85980 Mon Sep 17 00:00:00 2001 From: Borja Outerelo Date: Fri, 7 Sep 2018 07:55:04 +0200 Subject: [PATCH 01/27] Refs #3333. First commit of the basic examples using strings and int32 --- example_publisher/CMakeLists.txt | 17 ++++++++++++ example_publisher/main.c | 35 +++++++++++++++++++++++++ example_publisher/package.xml | 16 +++++++++++ example_publisher_int32/CMakeLists.txt | 17 ++++++++++++ example_publisher_int32/main.c | 26 ++++++++++++++++++ example_publisher_int32/package.xml | 16 +++++++++++ example_subscriber/CMakeLists.txt | 17 ++++++++++++ example_subscriber/main.c | 26 ++++++++++++++++++ example_subscriber/package.xml | 16 +++++++++++ example_subscriber_int32/CMakeLists.txt | 17 ++++++++++++ example_subscriber_int32/main.c | 26 ++++++++++++++++++ example_subscriber_int32/package.xml | 16 +++++++++++ 12 files changed, 245 insertions(+) create mode 100644 example_publisher/CMakeLists.txt create mode 100644 example_publisher/main.c create mode 100644 example_publisher/package.xml create mode 100644 example_publisher_int32/CMakeLists.txt create mode 100644 example_publisher_int32/main.c create mode 100644 example_publisher_int32/package.xml create mode 100644 example_subscriber/CMakeLists.txt create mode 100644 example_subscriber/main.c create mode 100644 example_subscriber/package.xml create mode 100644 example_subscriber_int32/CMakeLists.txt create mode 100644 example_subscriber_int32/main.c create mode 100644 example_subscriber_int32/package.xml diff --git a/example_publisher/CMakeLists.txt b/example_publisher/CMakeLists.txt new file mode 100644 index 0000000..ecb3a95 --- /dev/null +++ b/example_publisher/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(example_publisher) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(example_publisher main.c) +ament_target_dependencies(example_publisher rclc std_msgs) + +install(TARGETS + example_publisher + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/example_publisher/main.c b/example_publisher/main.c new file mode 100644 index 0000000..5624e3a --- /dev/null +++ b/example_publisher/main.c @@ -0,0 +1,35 @@ +#include +#include + +#include + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_publisher_t* publisher = + rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "publisher_example", 1); + + std_msgs__msg__String msg; + char buff[128] = {0}; + msg.data.data = buff; + msg.data.capacity = sizeof(buff); + msg.data.size = 0; + + int num = 0; + while (rclc_ok()) + { + msg.data.size = snprintf(msg.data.data, msg.data.capacity, "Hello World %i", num++); + if (msg.data.size > msg.data.capacity) + msg.data.size = 0; + + printf("Sending: '%s'\n", msg.data.data); + rclc_publish(publisher, (const void*)&msg); + rclc_spin_node_once(node, 500); + } + rclc_destroy_publisher(publisher); + rclc_destroy_node(node); + return 0; +} diff --git a/example_publisher/package.xml b/example_publisher/package.xml new file mode 100644 index 0000000..5406617 --- /dev/null +++ b/example_publisher/package.xml @@ -0,0 +1,16 @@ + + + + example_publisher + 0.0.1 + Example of a publisher + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/example_publisher_int32/CMakeLists.txt b/example_publisher_int32/CMakeLists.txt new file mode 100644 index 0000000..e6036d5 --- /dev/null +++ b/example_publisher_int32/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(example_publisher_int32) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(example_publisher_int32 main.c) +ament_target_dependencies(example_publisher_int32 rclc std_msgs) + +install(TARGETS + example_publisher_int32 + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/example_publisher_int32/main.c b/example_publisher_int32/main.c new file mode 100644 index 0000000..ea05f86 --- /dev/null +++ b/example_publisher_int32/main.c @@ -0,0 +1,26 @@ +#include +#include + +#include + +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "publisher_example", 1); + + std_msgs__msg__Int32 msg; + msg.data = -1; + + while (rclc_ok()) + { + printf("Sending: '%i'\n", msg.data++); + rclc_publish(publisher, (const void*)&msg); + rclc_spin_node_once(node, 500); + } + rclc_destroy_publisher(publisher); + rclc_destroy_node(node); + return 0; +} \ No newline at end of file diff --git a/example_publisher_int32/package.xml b/example_publisher_int32/package.xml new file mode 100644 index 0000000..4cb8206 --- /dev/null +++ b/example_publisher_int32/package.xml @@ -0,0 +1,16 @@ + + + + example_publisher_int32 + 0.0.1 + Example of a publisher using int32 + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/example_subscriber/CMakeLists.txt b/example_subscriber/CMakeLists.txt new file mode 100644 index 0000000..7ac3d19 --- /dev/null +++ b/example_subscriber/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(example_subscriber) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(example_subscriber main.c) +ament_target_dependencies(example_subscriber rclc std_msgs) + +install(TARGETS + example_subscriber + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/example_subscriber/main.c b/example_subscriber/main.c new file mode 100644 index 0000000..db9b019 --- /dev/null +++ b/example_subscriber/main.c @@ -0,0 +1,26 @@ +#include +#include + +#include + +void on_message(const void* msgin) +{ + const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; + printf("I heard: [%s]\n", msg->data.data); +} + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), + "subscription_example", on_message, 1, false); + + rclc_spin_node(node); + + rclc_destroy_subscription(sub); + rclc_destroy_node(node); + return 0; +} diff --git a/example_subscriber/package.xml b/example_subscriber/package.xml new file mode 100644 index 0000000..ffdcfd8 --- /dev/null +++ b/example_subscriber/package.xml @@ -0,0 +1,16 @@ + + + + example_subscriber + 0.0.1 + Example of a subscriber + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/example_subscriber_int32/CMakeLists.txt b/example_subscriber_int32/CMakeLists.txt new file mode 100644 index 0000000..7675a04 --- /dev/null +++ b/example_subscriber_int32/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(example_subscriber_int32) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(example_subscriber_int32 main.c) +ament_target_dependencies(example_subscriber_int32 rclc std_msgs) + +install(TARGETS + example_subscriber_int32 + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/example_subscriber_int32/main.c b/example_subscriber_int32/main.c new file mode 100644 index 0000000..9184596 --- /dev/null +++ b/example_subscriber_int32/main.c @@ -0,0 +1,26 @@ +#include +#include + +#include + +void on_message(const void* msgin) +{ + const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; + printf("I heard: [%i]\n", msg->data); +} + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), + "subscription_example", on_message, 1, false); + + rclc_spin_node(node); + + rclc_destroy_subscription(sub); + rclc_destroy_node(node); + return 0; +} diff --git a/example_subscriber_int32/package.xml b/example_subscriber_int32/package.xml new file mode 100644 index 0000000..e66c894 --- /dev/null +++ b/example_subscriber_int32/package.xml @@ -0,0 +1,16 @@ + + + + example_subscriber_int32 + 0.0.1 + Example of a subscriber using int32 + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + From 5def0c7d864c1c415916db5353f068482a009a2f Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Fri, 14 Sep 2018 11:36:49 +0200 Subject: [PATCH 02/27] Refs #3364. Not working yet --- actuator/CMakeLists.txt | 17 ++++++++++++++ actuator/COLCON_IGNORE | 0 actuator/main.c | 42 ++++++++++++++++++++++++++++++++++ actuator/package.xml | 16 +++++++++++++ display/CMakeLists.txt | 17 ++++++++++++++ display/COLCON_IGNORE | 0 display/main.c | 35 ++++++++++++++++++++++++++++ display/package.xml | 16 +++++++++++++ position_sensor/CMakeLists.txt | 17 ++++++++++++++ position_sensor/COLCON_IGNORE | 0 position_sensor/main.c | 35 ++++++++++++++++++++++++++++ position_sensor/package.xml | 16 +++++++++++++ 12 files changed, 211 insertions(+) create mode 100644 actuator/CMakeLists.txt create mode 100644 actuator/COLCON_IGNORE create mode 100644 actuator/main.c create mode 100644 actuator/package.xml create mode 100644 display/CMakeLists.txt create mode 100644 display/COLCON_IGNORE create mode 100644 display/main.c create mode 100644 display/package.xml create mode 100644 position_sensor/CMakeLists.txt create mode 100644 position_sensor/COLCON_IGNORE create mode 100644 position_sensor/main.c create mode 100644 position_sensor/package.xml diff --git a/actuator/CMakeLists.txt b/actuator/CMakeLists.txt new file mode 100644 index 0000000..6f50ce0 --- /dev/null +++ b/actuator/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(actuator) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(actuator main.c) +ament_target_dependencies(actuator rclc std_msgs) + +install(TARGETS + actuator + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/actuator/COLCON_IGNORE b/actuator/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/actuator/main.c b/actuator/main.c new file mode 100644 index 0000000..a2ac7d6 --- /dev/null +++ b/actuator/main.c @@ -0,0 +1,42 @@ +#include +#include +#include + +#include + +void on_message(const void* msgin) +{ + const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; + + + printf("I heard: [%i]\n", msg->data); + + + // Publish warning if value is less than 1000 + if (msg->data <= 1000) + { + std_msgs__msg__String Warning; + Warning.data = "Warning"; + + rclc_publish(publisher, (const void*)&Warning); + } + +} + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("actuator", ""); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", on_message, 1, false); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "Warning", 1); + + rclc_spin_node(node); + + if (sub) rclc_destroy_subscription(sub); + if (publisher) rclc_destroy_publisher(publisher); + if (node) rclc_destroy_node(node); + + return 0; +} diff --git a/actuator/package.xml b/actuator/package.xml new file mode 100644 index 0000000..391da4f --- /dev/null +++ b/actuator/package.xml @@ -0,0 +1,16 @@ + + + + actuator + 0.0.1 + Demo. Actuator node + Javier Moreno + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/display/CMakeLists.txt b/display/CMakeLists.txt new file mode 100644 index 0000000..793b9d6 --- /dev/null +++ b/display/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(display) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(display REQUIRED) + +add_executable(display main.c) +ament_target_dependencies(display rclc std_msgs) + +install(TARGETS + display + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/display/COLCON_IGNORE b/display/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/display/main.c b/display/main.c new file mode 100644 index 0000000..a69f54c --- /dev/null +++ b/display/main.c @@ -0,0 +1,35 @@ +#include +#include + +#include +#include +#include + +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("display", ""); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", 1); + + std_msgs__msg__Float64 msg; + msg.data = 0; + double Count = 0; + srand((unsigned) time(&t)); + + while (rclc_ok()) + { + // Emulate senoidal change position 2000 to 0 + Count += 0.1; + msg.data = 1000* sin(Count) + 1000; + + rclc_publish(publisher, (const void*)&msg); + rclc_spin_node_once(node, (rand() % 900 + 100)); + } + + if (publisher) rclc_destroy_publisher(publisher); + if (node) rclc_destroy_node(node); + + return 0; +} \ No newline at end of file diff --git a/display/package.xml b/display/package.xml new file mode 100644 index 0000000..20fb8d5 --- /dev/null +++ b/display/package.xml @@ -0,0 +1,16 @@ + + + + display + 0.0.1 + Demo. Display on screen any message + Javier Moreno + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/position_sensor/CMakeLists.txt b/position_sensor/CMakeLists.txt new file mode 100644 index 0000000..7dfff4d --- /dev/null +++ b/position_sensor/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(position_sensor) + +find_package(ament_cmake REQUIRED) +find_package(rclc REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(position_sensor main.c) +ament_target_dependencies(position_sensor rclc std_msgs) + +install(TARGETS + position_sensor + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/position_sensor/COLCON_IGNORE b/position_sensor/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/position_sensor/main.c b/position_sensor/main.c new file mode 100644 index 0000000..6de44d1 --- /dev/null +++ b/position_sensor/main.c @@ -0,0 +1,35 @@ +#include +#include + +#include +#include +#include + +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("position_sensor", ""); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", 1); + + std_msgs__msg__Float64 msg; + msg.data = 0; + double Count = 0; + srand((unsigned) time(&t)); + + while (rclc_ok()) + { + // Emulate senoidal change position 2000 to 0 + Count += 0.1; + msg.data = 1000* sin(Count) + 1000; + + rclc_publish(publisher, (const void*)&msg); + rclc_spin_node_once(node, (rand() % 900 + 100)); + } + + if (publisher) rclc_destroy_publisher(publisher); + if (node) rclc_destroy_node(node); + + return 0; +} \ No newline at end of file diff --git a/position_sensor/package.xml b/position_sensor/package.xml new file mode 100644 index 0000000..96bfe20 --- /dev/null +++ b/position_sensor/package.xml @@ -0,0 +1,16 @@ + + + + position_sensor + 0.0.1 + Demo. Position sensor node + Javier Moreno + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + From c39d7f4d4ae0d4461aa61a0ef22b9d756f10e57c Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Fri, 14 Sep 2018 12:44:00 +0200 Subject: [PATCH 03/27] Refs #3364. Build ok. Not tested. --- actuator/COLCON_IGNORE | 0 actuator/main.c | 19 +++++++------- display/CMakeLists.txt | 2 +- display/COLCON_IGNORE | 0 display/main.c | 45 ++++++++++++++++------------------ position_sensor/CMakeLists.txt | 2 ++ position_sensor/COLCON_IGNORE | 0 position_sensor/main.c | 1 + 8 files changed, 35 insertions(+), 34 deletions(-) delete mode 100644 actuator/COLCON_IGNORE delete mode 100644 display/COLCON_IGNORE delete mode 100644 position_sensor/COLCON_IGNORE diff --git a/actuator/COLCON_IGNORE b/actuator/COLCON_IGNORE deleted file mode 100644 index e69de29..0000000 diff --git a/actuator/main.c b/actuator/main.c index a2ac7d6..c98ce74 100644 --- a/actuator/main.c +++ b/actuator/main.c @@ -1,23 +1,24 @@ #include -#include -#include +#include +#include #include +rclc_publisher_t* publisher; + + void on_message(const void* msgin) { const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; - - printf("I heard: [%i]\n", msg->data); - - // Publish warning if value is less than 1000 if (msg->data <= 1000) { std_msgs__msg__String Warning; - Warning.data = "Warning"; - + Warning.data.data = "Warning"; + Warning.data.size = strlen(Warning.data.data); + Warning.data.capacity = strlen(Warning.data.data); + rclc_publish(publisher, (const void*)&Warning); } @@ -30,7 +31,7 @@ int main(int argc, char* argv[]) rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("actuator", ""); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", on_message, 1, false); - rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "Warning", 1); + publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "Warning", 1); rclc_spin_node(node); diff --git a/display/CMakeLists.txt b/display/CMakeLists.txt index 793b9d6..8fbfb62 100644 --- a/display/CMakeLists.txt +++ b/display/CMakeLists.txt @@ -4,7 +4,7 @@ project(display) find_package(ament_cmake REQUIRED) find_package(rclc REQUIRED) -find_package(display REQUIRED) +find_package(std_msgs REQUIRED) add_executable(display main.c) ament_target_dependencies(display rclc std_msgs) diff --git a/display/COLCON_IGNORE b/display/COLCON_IGNORE deleted file mode 100644 index e69de29..0000000 diff --git a/display/main.c b/display/main.c index a69f54c..4abb2c1 100644 --- a/display/main.c +++ b/display/main.c @@ -1,35 +1,32 @@ #include -#include +#include #include -#include -#include + +static unsigned WaringCount = 0; + +void on_message(const void* msgin) +{ + const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; + + + printf("[%i] %s\n", WaringCount++, msg->data.data); +} + int main(int argc, char *argv[]) { (void)argc; (void)argv; + rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("display", ""); - rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", 1); - - std_msgs__msg__Float64 msg; - msg.data = 0; - double Count = 0; - srand((unsigned) time(&t)); - - while (rclc_ok()) - { - // Emulate senoidal change position 2000 to 0 - Count += 0.1; - msg.data = 1000* sin(Count) + 1000; - - rclc_publish(publisher, (const void*)&msg); - rclc_spin_node_once(node, (rand() % 900 + 100)); - } - - if (publisher) rclc_destroy_publisher(publisher); - if (node) rclc_destroy_node(node); - return 0; + rclc_node_t* node = rclc_create_node("display", ""); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "Warning", on_message, 1, false); + + rclc_spin_node(node); + + if (sub) rclc_destroy_subscription(sub); + if (node) rclc_destroy_node(node); + } \ No newline at end of file diff --git a/position_sensor/CMakeLists.txt b/position_sensor/CMakeLists.txt index 7dfff4d..332f1eb 100644 --- a/position_sensor/CMakeLists.txt +++ b/position_sensor/CMakeLists.txt @@ -9,6 +9,8 @@ find_package(std_msgs REQUIRED) add_executable(position_sensor main.c) ament_target_dependencies(position_sensor rclc std_msgs) +target_link_libraries(position_sensor m) + install(TARGETS position_sensor DESTINATION lib/${PROJECT_NAME} diff --git a/position_sensor/COLCON_IGNORE b/position_sensor/COLCON_IGNORE deleted file mode 100644 index e69de29..0000000 diff --git a/position_sensor/main.c b/position_sensor/main.c index 6de44d1..a7e09e5 100644 --- a/position_sensor/main.c +++ b/position_sensor/main.c @@ -16,6 +16,7 @@ int main(int argc, char *argv[]) std_msgs__msg__Float64 msg; msg.data = 0; double Count = 0; + time_t t; srand((unsigned) time(&t)); while (rclc_ok()) From d5dfb7c4f4af593dc23e7c92973244853957704c Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Fri, 14 Sep 2018 13:12:20 +0200 Subject: [PATCH 04/27] Refs #3364. Little changes --- actuator/main.c | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/actuator/main.c b/actuator/main.c index c98ce74..888e012 100644 --- a/actuator/main.c +++ b/actuator/main.c @@ -12,16 +12,24 @@ void on_message(const void* msgin) const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; // Publish warning if value is less than 1000 - if (msg->data <= 1000) + if (msg->data <= 500) { std_msgs__msg__String Warning; - Warning.data.data = "Warning"; + Warning.data.data = "Failure!!"; + Warning.data.size = strlen(Warning.data.data); + Warning.data.capacity = strlen(Warning.data.data); + + rclc_publish(publisher, (const void*)&Warning); + } + else if (msg->data <= 1000) + { + std_msgs__msg__String Warning; + Warning.data.data = "Warning!!"; Warning.data.size = strlen(Warning.data.data); Warning.data.capacity = strlen(Warning.data.data); rclc_publish(publisher, (const void*)&Warning); } - } int main(int argc, char* argv[]) From 7f1b1826c3985fb882a8d29f9bb2cb33a076e07e Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Mon, 17 Sep 2018 08:02:22 +0200 Subject: [PATCH 05/27] Refs #3364. --- actuator/main.c | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/actuator/main.c b/actuator/main.c index 888e012..60b3554 100644 --- a/actuator/main.c +++ b/actuator/main.c @@ -4,10 +4,10 @@ #include -rclc_publisher_t* publisher; +static rclc_publisher_t* publisher; -void on_message(const void* msgin) +void altitude_on_message(const void* msgin) { const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; @@ -32,18 +32,26 @@ void on_message(const void* msgin) } } + +void engine_on_message(const void* msgin) +{ + const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; +} + int main(int argc, char* argv[]) { (void)argc; (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("actuator", ""); - rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", on_message, 1, false); - publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "Warning", 1); + rclc_subscription_t* altitude_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", altitude_on_message, 1, false); + rclc_subscription_t* engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "engine_power", engine_on_message, 1, false); + publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "status_report", 1); rclc_spin_node(node); - if (sub) rclc_destroy_subscription(sub); + if (altitude_sub) rclc_destroy_subscription(altitude_sub); + if (engine_sub) rclc_destroy_subscription(engine_sub); if (publisher) rclc_destroy_publisher(publisher); if (node) rclc_destroy_node(node); From 90ef71a13fd6b4f127820814620df0b88ab9902e Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Mon, 17 Sep 2018 16:10:15 +0200 Subject: [PATCH 06/27] Added demo ROS2 --- external_node/CMakeLists.txt | 25 +++++++++++++++ external_node/COLCON_IGNORE | 0 external_node/README.md | 5 +++ external_node/main.cpp | 62 ++++++++++++++++++++++++++++++++++++ external_node/package.xml | 23 +++++++++++++ 5 files changed, 115 insertions(+) create mode 100644 external_node/CMakeLists.txt create mode 100644 external_node/COLCON_IGNORE create mode 100644 external_node/README.md create mode 100644 external_node/main.cpp create mode 100644 external_node/package.xml diff --git a/external_node/CMakeLists.txt b/external_node/CMakeLists.txt new file mode 100644 index 0000000..4f6e690 --- /dev/null +++ b/external_node/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.5) +project(external_node) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(external_node main.cpp) +ament_target_dependencies(external_node rclcpp std_msgs) + +install(TARGETS + external_node + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/external_node/COLCON_IGNORE b/external_node/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/external_node/README.md b/external_node/README.md new file mode 100644 index 0000000..a8cdda4 --- /dev/null +++ b/external_node/README.md @@ -0,0 +1,5 @@ +# Minimal publisher examples + +This package contains a few different strategies for creating short nodes which blast out messages. +The `talker_timer_lambda` and `talker_timer_member_function` recipes create subclasses of `rclcpp::Node` and set up an `rclcpp::timer` to periodically call functions which publish messages. +The `talker_without_subclass` recipe instead instantiates a `rclcpp::Node` object *without* subclassing it, which works, but is not compatible with composition, and thus is no longer the recommended style for ROS 2 coding. diff --git a/external_node/main.cpp b/external_node/main.cpp new file mode 100644 index 0000000..7473462 --- /dev/null +++ b/external_node/main.cpp @@ -0,0 +1,62 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/float64.hpp" +#include "std_msgs/msg/string.hpp" +using std::placeholders::_1; + +class ExternalNode : public rclcpp::Node +{ +public: + ExternalNode() : Node("external_node") + { + power_publisher_ = this->create_publisher("engine_power"); + + altitude_subscription_ = this->create_subscription("status_report", std::bind(&ExternalNode::topic_callback, this, _1)); + } + +private: + rclcpp::Publisher::SharedPtr power_publisher_; + rclcpp::Subscription::SharedPtr altitude_subscription_; + + void topic_callback(const std_msgs::msg::String::SharedPtr msg) + { + if (strcmp(msg->data.c_str(), "Failure!!") == 0) + { + //std_msgs__msg__Float64 message; + auto message = std_msgs::msg::Float64(); + message.data = 10; + this->power_publisher_->publish(message); + } + else if (strcmp(msg->data.c_str(), "Failure!!") == 0) + { + auto message = std_msgs::msg::Float64(); + message.data = 5; + this->power_publisher_->publish(message); + } + else + { + RCLCPP_INFO(this->get_logger(), "Unkwnow status: '%s'", msg->data.c_str()) + } + } +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/external_node/package.xml b/external_node/package.xml new file mode 100644 index 0000000..b92af4f --- /dev/null +++ b/external_node/package.xml @@ -0,0 +1,23 @@ + + + + external_node + 0.0.1 + Demo. Node running on ros2 + Javier Moreno + Apache License 2.0 + Javier Moreno + + ament_cmake + + rclcpp + std_msgs + + rclcpp + std_msgs + + + ament_cmake + + + From f9048d6c58c3385b0e07f833c286c172e2843864 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Mon, 24 Sep 2018 15:39:45 +0200 Subject: [PATCH 07/27] Refs #3364 --- actuator/CMakeLists.txt | 2 + actuator/main.c | 66 ++++++++------- .../CMakeLists.txt | 12 +-- altitude_sensor/main.c | 74 +++++++++++++++++ .../package.xml | 2 +- {external_node => control}/CMakeLists.txt | 8 +- {external_node => control}/COLCON_IGNORE | 0 {external_node => control}/README.md | 0 control/main.cpp | 83 +++++++++++++++++++ {external_node => control}/package.xml | 2 +- display/CMakeLists.txt | 2 + display/main.c | 80 ++++++++++++++++-- example_publisher/CMakeLists.txt | 2 + example_publisher_int32/main.c | 26 +++++- example_subscriber/CMakeLists.txt | 2 + example_subscriber_int32/main.c | 3 +- external_node/main.cpp | 62 -------------- position_sensor/main.c | 36 -------- test_custom_msg/CMakeLists.txt | 30 +++++++ test_custom_msg/msg/AAAATest.msg | 14 ++++ test_custom_msg/package.xml | 26 ++++++ 21 files changed, 379 insertions(+), 153 deletions(-) rename {position_sensor => altitude_sensor}/CMakeLists.txt (50%) create mode 100644 altitude_sensor/main.c rename {position_sensor => altitude_sensor}/package.xml (94%) rename {external_node => control}/CMakeLists.txt (75%) rename {external_node => control}/COLCON_IGNORE (100%) rename {external_node => control}/README.md (100%) create mode 100644 control/main.cpp rename {external_node => control}/package.xml (95%) delete mode 100644 external_node/main.cpp delete mode 100644 position_sensor/main.c create mode 100644 test_custom_msg/CMakeLists.txt create mode 100644 test_custom_msg/msg/AAAATest.msg create mode 100644 test_custom_msg/package.xml diff --git a/actuator/CMakeLists.txt b/actuator/CMakeLists.txt index 6f50ce0..214832e 100644 --- a/actuator/CMakeLists.txt +++ b/actuator/CMakeLists.txt @@ -14,4 +14,6 @@ install(TARGETS DESTINATION lib/${PROJECT_NAME} ) +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + ament_package() diff --git a/actuator/main.c b/actuator/main.c index 60b3554..96835bd 100644 --- a/actuator/main.c +++ b/actuator/main.c @@ -1,59 +1,61 @@ #include #include -#include +#include +#include #include -static rclc_publisher_t* publisher; +static rclc_publisher_t* engine_pub; +static uint32_t engine_power = 100; - -void altitude_on_message(const void* msgin) +void engine_on_message(const void* msgin) { - const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; - - // Publish warning if value is less than 1000 - if (msg->data <= 500) + + const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; + + if (msg->data + engine_power > 0) { - std_msgs__msg__String Warning; - Warning.data.data = "Failure!!"; - Warning.data.size = strlen(Warning.data.data); - Warning.data.capacity = strlen(Warning.data.data); - - rclc_publish(publisher, (const void*)&Warning); + engine_power += msg->data; } - else if (msg->data <= 1000) + else { - std_msgs__msg__String Warning; - Warning.data.data = "Warning!!"; - Warning.data.size = strlen(Warning.data.data); - Warning.data.capacity = strlen(Warning.data.data); - - rclc_publish(publisher, (const void*)&Warning); + engine_power = 0; } -} - -void engine_on_message(const void* msgin) -{ - const std_msgs__msg__Float64* msg = (const std_msgs__msg__Float64*)msgin; + // Publish new altitude + std_msgs__msg__UInt32 msg_out; + msg_out.data = engine_power; + rclc_publish(engine_pub, (const void*)&msg_out); } int main(int argc, char* argv[]) { (void)argc; (void)argv; + + rclc_node_t* node = NULL; + rclc_subscription_t* engine_sub = NULL; + + + rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("actuator", ""); - rclc_subscription_t* altitude_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", altitude_on_message, 1, false); - rclc_subscription_t* engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "engine_power", engine_on_message, 1, false); - publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "status_report", 1); + node = rclc_create_node("actuator", ""); + engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", engine_on_message, 1, false); + engine_pub = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", 1); + + // Publish new altitude + std_msgs__msg__UInt32 msg_out; + msg_out.data = engine_power; + rclc_publish(engine_pub, (const void*)&msg_out); rclc_spin_node(node); - if (altitude_sub) rclc_destroy_subscription(altitude_sub); + //if (altitude_sub) rclc_destroy_subscription(altitude_sub); if (engine_sub) rclc_destroy_subscription(engine_sub); - if (publisher) rclc_destroy_publisher(publisher); + if (engine_pub) rclc_destroy_publisher(engine_pub); if (node) rclc_destroy_node(node); + printf("Actuator node closed.\n"); + return 0; } diff --git a/position_sensor/CMakeLists.txt b/altitude_sensor/CMakeLists.txt similarity index 50% rename from position_sensor/CMakeLists.txt rename to altitude_sensor/CMakeLists.txt index 332f1eb..6165086 100644 --- a/position_sensor/CMakeLists.txt +++ b/altitude_sensor/CMakeLists.txt @@ -1,19 +1,21 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(position_sensor) +project(altitude_sensor) find_package(ament_cmake REQUIRED) find_package(rclc REQUIRED) find_package(std_msgs REQUIRED) -add_executable(position_sensor main.c) -ament_target_dependencies(position_sensor rclc std_msgs) +add_executable(altitude_sensor main.c) +ament_target_dependencies(altitude_sensor rclc std_msgs) -target_link_libraries(position_sensor m) +target_link_libraries(altitude_sensor m) install(TARGETS - position_sensor + altitude_sensor DESTINATION lib/${PROJECT_NAME} ) +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + ament_package() diff --git a/altitude_sensor/main.c b/altitude_sensor/main.c new file mode 100644 index 0000000..c4c4604 --- /dev/null +++ b/altitude_sensor/main.c @@ -0,0 +1,74 @@ +#include +#include +#include + +#include +#include +#include + + +static uint32_t Offset = 0; + +/** + * @brief + * + * @param msgin + */ +void on_power_message(const void* msgin) +{ + std_msgs__msg__UInt32* msg = (std_msgs__msg__UInt32*)msgin; + + Offset = msg->data; +} + + +/** + * @brief + * + * @param argc + * @param argv + * @return int + */ +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + + rclc_node_t* node = NULL; + rclc_publisher_t* publisher = NULL; + rclc_subscription_t* power_subscription = NULL; + + + node = rclc_create_node("altitude_sensor", ""); + publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", 1); + //power_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", on_power_message, 1, false); + + double Altitude = 1000; + double Count = 0; + time_t t; + srand((unsigned) time(&t)); + + while (rclc_ok()) + { + Count += 0.1; + Altitude += (rand() % 10) * cos(Count); + + + // Publish new altitude + std_msgs__msg__Float64 msg; + msg.data = Altitude + Offset; + rclc_publish(publisher, (const void*)&msg); + + + // Spin node + rclc_spin_node_once(node, 1); + } + + if (publisher) rclc_destroy_publisher(publisher); + if (power_subscription) rclc_destroy_publisher(power_subscription); + if (node) rclc_destroy_node(node); + + printf("altitude sendor closed.\n"); + return 0; +} \ No newline at end of file diff --git a/position_sensor/package.xml b/altitude_sensor/package.xml similarity index 94% rename from position_sensor/package.xml rename to altitude_sensor/package.xml index 96bfe20..547fcd9 100644 --- a/position_sensor/package.xml +++ b/altitude_sensor/package.xml @@ -1,7 +1,7 @@ - position_sensor + altitude_sensor 0.0.1 Demo. Position sensor node Javier Moreno diff --git a/external_node/CMakeLists.txt b/control/CMakeLists.txt similarity index 75% rename from external_node/CMakeLists.txt rename to control/CMakeLists.txt index 4f6e690..bb1aded 100644 --- a/external_node/CMakeLists.txt +++ b/control/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(external_node) +project(control) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -14,11 +14,11 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) -add_executable(external_node main.cpp) -ament_target_dependencies(external_node rclcpp std_msgs) +add_executable(control main.cpp) +ament_target_dependencies(control rclcpp std_msgs) install(TARGETS - external_node + control DESTINATION lib/${PROJECT_NAME} ) diff --git a/external_node/COLCON_IGNORE b/control/COLCON_IGNORE similarity index 100% rename from external_node/COLCON_IGNORE rename to control/COLCON_IGNORE diff --git a/external_node/README.md b/control/README.md similarity index 100% rename from external_node/README.md rename to control/README.md diff --git a/control/main.cpp b/control/main.cpp new file mode 100644 index 0000000..17d87f5 --- /dev/null +++ b/control/main.cpp @@ -0,0 +1,83 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/float64.hpp" +#include "std_msgs/msg/int32.hpp" +#include "std_msgs/msg/string.hpp" +using std::placeholders::_1; + +class ExternalNode : public rclcpp::Node +{ +public: + ExternalNode() : Node("control") + { + engine_power_publisher_ = this->create_publisher("std_msgs_msg_Int32"); + warn_publisher_ = this->create_publisher("std_msgs_msg_String"); + + altitude_subscription_ = this->create_subscription("std_msgs_msg_Float64", std::bind(&ExternalNode::topic_callback, this, _1)); + } + +private: + rclcpp::Publisher::SharedPtr engine_power_publisher_; + rclcpp::Publisher::SharedPtr warn_publisher_; + rclcpp::Subscription::SharedPtr altitude_subscription_; + + void topic_callback(const std_msgs::msg::Float64::SharedPtr msg) + { + // Warning + if (msg->data <= 500) + { + { + auto message = std_msgs::msg::String(); + message.data = "Failure!!"; + RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()) + this->warn_publisher_->publish(message); + } + + { + auto message = std_msgs::msg::Int32(); + message.data = 10; + this->engine_power_publisher_->publish(message); + } + + } + + // Failure + else if (msg->data <= 1000) + { + { + auto message = std_msgs::msg::String(); + message.data = "Warning!!"; + RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()) + this->warn_publisher_->publish(message); + } + + { + auto message = std_msgs::msg::Int32(); + message.data = 5; + this->engine_power_publisher_->publish(message); + } + + } + } +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/external_node/package.xml b/control/package.xml similarity index 95% rename from external_node/package.xml rename to control/package.xml index b92af4f..e66e087 100644 --- a/external_node/package.xml +++ b/control/package.xml @@ -1,7 +1,7 @@ - external_node + control 0.0.1 Demo. Node running on ros2 Javier Moreno diff --git a/display/CMakeLists.txt b/display/CMakeLists.txt index 8fbfb62..6671b2f 100644 --- a/display/CMakeLists.txt +++ b/display/CMakeLists.txt @@ -14,4 +14,6 @@ install(TARGETS DESTINATION lib/${PROJECT_NAME} ) +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + ament_package() diff --git a/display/main.c b/display/main.c index 4abb2c1..c89dda9 100644 --- a/display/main.c +++ b/display/main.c @@ -1,32 +1,100 @@ #include #include +#include +#include +#include #include -static unsigned WaringCount = 0; -void on_message(const void* msgin) +static float altitude; +static uint32_t engine_power; +static unsigned it; +static char Alert[200]; + +/** + * @brief Update screen + * + */ +void UpdateDisplay() +{ + printf("\r[received messages: %7u]\t [Altitude: %.2f]\t [Engine power: %5u]\t [Status: %s]\t\t\t", it++, altitude, engine_power, Alert); +} + + +/** + * @brief new alert callback + * + * @param msgin + */ +void on_alert_message(const void* msgin) { const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; + strcpy(Alert, msg->data.data); + + UpdateDisplay(); +} - printf("[%i] %s\n", WaringCount++, msg->data.data); +/** + * @brief new altitude calback + * + * @param msgin + */ +void on_altitude_message(const void* msgin) +{ + std_msgs__msg__Float64* msg = (std_msgs__msg__Float64*)msgin; + + altitude = msg->data; + UpdateDisplay(); +} + +/** + * @brief + * + * @param msgin + */ +void on_power_message(const void* msgin) +{ + std_msgs__msg__UInt32* msg = (std_msgs__msg__UInt32*)msgin; + + engine_power = msg->data; + UpdateDisplay(); } +/** + * @brief Main + * + * @param argc + * @param argv + * @return int + */ int main(int argc, char *argv[]) { (void)argc; (void)argv; + rclc_node_t* node = NULL; + rclc_subscription_t* alert_subscription = NULL; + rclc_subscription_t* altitude_subscription = NULL; + rclc_subscription_t* power_subscription = NULL; + + rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("display", ""); - rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "Warning", on_message, 1, false); + node = rclc_create_node("display", ""); + + alert_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_alert_message, 1, false); + altitude_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", on_altitude_message, 1, false); + power_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", on_power_message, 1, false); rclc_spin_node(node); - if (sub) rclc_destroy_subscription(sub); + if (alert_subscription) rclc_destroy_subscription(alert_subscription); + if (altitude_subscription) rclc_destroy_subscription(altitude_subscription); if (node) rclc_destroy_node(node); + printf("Display node closed."); + } \ No newline at end of file diff --git a/example_publisher/CMakeLists.txt b/example_publisher/CMakeLists.txt index ecb3a95..6f45c4f 100644 --- a/example_publisher/CMakeLists.txt +++ b/example_publisher/CMakeLists.txt @@ -14,4 +14,6 @@ install(TARGETS DESTINATION lib/${PROJECT_NAME} ) +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + ament_package() diff --git a/example_publisher_int32/main.c b/example_publisher_int32/main.c index ea05f86..4eef187 100644 --- a/example_publisher_int32/main.c +++ b/example_publisher_int32/main.c @@ -7,9 +7,10 @@ int main(int argc, char *argv[]) { (void)argc; (void)argv; + rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("publisher_node", ""); - rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "publisher_example", 1); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", 1); std_msgs__msg__Int32 msg; msg.data = -1; @@ -18,9 +19,26 @@ int main(int argc, char *argv[]) { printf("Sending: '%i'\n", msg.data++); rclc_publish(publisher, (const void*)&msg); - rclc_spin_node_once(node, 500); + for (unsigned i=0; i < 999999; i++){} + rclc_spin_node_once(node, 1000); + } + + if (publisher) + { + rclc_destroy_publisher(publisher); + } + else + { + printf("Create publisher error\n"); + } + + if (node) + { + rclc_destroy_node(node); + } + else + { + printf("Create node error\n"); } - rclc_destroy_publisher(publisher); - rclc_destroy_node(node); return 0; } \ No newline at end of file diff --git a/example_subscriber/CMakeLists.txt b/example_subscriber/CMakeLists.txt index 7ac3d19..3b0d23e 100644 --- a/example_subscriber/CMakeLists.txt +++ b/example_subscriber/CMakeLists.txt @@ -14,4 +14,6 @@ install(TARGETS DESTINATION lib/${PROJECT_NAME} ) +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + ament_package() diff --git a/example_subscriber_int32/main.c b/example_subscriber_int32/main.c index 9184596..0f7816b 100644 --- a/example_subscriber_int32/main.c +++ b/example_subscriber_int32/main.c @@ -15,8 +15,7 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("subscription_node", ""); - rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), - "subscription_example", on_message, 1, false); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", on_message, 1, false); rclc_spin_node(node); diff --git a/external_node/main.cpp b/external_node/main.cpp deleted file mode 100644 index 7473462..0000000 --- a/external_node/main.cpp +++ /dev/null @@ -1,62 +0,0 @@ -// Copyright 2016 Open Source Robotics Foundation, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/float64.hpp" -#include "std_msgs/msg/string.hpp" -using std::placeholders::_1; - -class ExternalNode : public rclcpp::Node -{ -public: - ExternalNode() : Node("external_node") - { - power_publisher_ = this->create_publisher("engine_power"); - - altitude_subscription_ = this->create_subscription("status_report", std::bind(&ExternalNode::topic_callback, this, _1)); - } - -private: - rclcpp::Publisher::SharedPtr power_publisher_; - rclcpp::Subscription::SharedPtr altitude_subscription_; - - void topic_callback(const std_msgs::msg::String::SharedPtr msg) - { - if (strcmp(msg->data.c_str(), "Failure!!") == 0) - { - //std_msgs__msg__Float64 message; - auto message = std_msgs::msg::Float64(); - message.data = 10; - this->power_publisher_->publish(message); - } - else if (strcmp(msg->data.c_str(), "Failure!!") == 0) - { - auto message = std_msgs::msg::Float64(); - message.data = 5; - this->power_publisher_->publish(message); - } - else - { - RCLCPP_INFO(this->get_logger(), "Unkwnow status: '%s'", msg->data.c_str()) - } - } -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} diff --git a/position_sensor/main.c b/position_sensor/main.c deleted file mode 100644 index a7e09e5..0000000 --- a/position_sensor/main.c +++ /dev/null @@ -1,36 +0,0 @@ -#include -#include - -#include -#include -#include - -int main(int argc, char *argv[]) -{ - (void)argc; - (void)argv; - rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("position_sensor", ""); - rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "position_sensor", 1); - - std_msgs__msg__Float64 msg; - msg.data = 0; - double Count = 0; - time_t t; - srand((unsigned) time(&t)); - - while (rclc_ok()) - { - // Emulate senoidal change position 2000 to 0 - Count += 0.1; - msg.data = 1000* sin(Count) + 1000; - - rclc_publish(publisher, (const void*)&msg); - rclc_spin_node_once(node, (rand() % 900 + 100)); - } - - if (publisher) rclc_destroy_publisher(publisher); - if (node) rclc_destroy_node(node); - - return 0; -} \ No newline at end of file diff --git a/test_custom_msg/CMakeLists.txt b/test_custom_msg/CMakeLists.txt new file mode 100644 index 0000000..07d75d3 --- /dev/null +++ b/test_custom_msg/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 3.5) + +project(test_custom_msg) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + # we dont use add_compile_options with pedantic in message packages + # because the Python C extensions dont comply with it + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +set(msg_files + "msg/AAAATest.msg" +) +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + DEPENDENCIES builtin_interfaces + ADD_LINTER_TESTS +) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/test_custom_msg/msg/AAAATest.msg b/test_custom_msg/msg/AAAATest.msg new file mode 100644 index 0000000..9531426 --- /dev/null +++ b/test_custom_msg/msg/AAAATest.msg @@ -0,0 +1,14 @@ +bool data1 +byte data2 +char data3 +float32 data4 +float64 data5 +int8 data6 +uint8 data7 +int16 data8 +uint16 data9 +int32 data10 +uint32 data11 +int64 data12 +uint64 data13 +string data14 \ No newline at end of file diff --git a/test_custom_msg/package.xml b/test_custom_msg/package.xml new file mode 100644 index 0000000..65565e3 --- /dev/null +++ b/test_custom_msg/package.xml @@ -0,0 +1,26 @@ + + + + test_custom_msg + 0.5.0 + Custom generated msg. + Javier Moreno + Apache License 2.0 + + ament_cmake + + rosidl_default_generators + + builtin_interfaces + + builtin_interfaces + rosidl_default_runtime + + ament_lint_common + + rosidl_interface_packages + + + ament_cmake + + From e70854f53e8ac95e31b01c4c0c10c3f0b37f3bad Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Tue, 25 Sep 2018 10:08:27 +0200 Subject: [PATCH 08/27] little changes --- display/main.c | 2 +- test_custom_msg/COLCON_IGNORE | 0 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 test_custom_msg/COLCON_IGNORE diff --git a/display/main.c b/display/main.c index c89dda9..7de14f9 100644 --- a/display/main.c +++ b/display/main.c @@ -18,7 +18,7 @@ static char Alert[200]; */ void UpdateDisplay() { - printf("\r[received messages: %7u]\t [Altitude: %.2f]\t [Engine power: %5u]\t [Status: %s]\t\t\t", it++, altitude, engine_power, Alert); + printf("\r[received messages: %7u]\t [Altitude: %5.2f]\t [Engine power: %5u]\t [Status: %10s]\t\t\t", it++, altitude, engine_power, Alert); } diff --git a/test_custom_msg/COLCON_IGNORE b/test_custom_msg/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 From 3c26d580f9be06ca0962c7f000f9a5bd6bf83a58 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Wed, 26 Sep 2018 08:46:58 +0200 Subject: [PATCH 09/27] added tests: mesgs, sub and pub --- actuator/CMakeLists.txt | 19 ---- actuator/main.c | 61 ----------- actuator/package.xml | 16 --- altitude_sensor/CMakeLists.txt | 21 ---- altitude_sensor/main.c | 74 ------------- altitude_sensor/package.xml | 16 --- control/CMakeLists.txt | 25 ----- control/COLCON_IGNORE | 0 control/README.md | 5 - control/main.cpp | 83 --------------- control/package.xml | 23 ---- display/CMakeLists.txt | 19 ---- display/main.c | 100 ------------------ display/package.xml | 16 --- example_publisher/CMakeLists.txt | 3 +- example_publisher/main.c | 41 +++++-- example_publisher/package.xml | 1 + example_publisher_int32/CMakeLists.txt | 17 --- example_publisher_int32/main.c | 44 -------- example_publisher_int32/package.xml | 16 --- example_subscriber/CMakeLists.txt | 3 +- example_subscriber/main.c | 9 +- example_subscriber/package.xml | 1 + example_subscriber_int32/CMakeLists.txt | 17 --- example_subscriber_int32/main.c | 25 ----- example_subscriber_int32/package.xml | 16 --- test_custom_msg/CMakeLists.txt | 5 +- test_custom_msg/COLCON_IGNORE | 0 test_custom_msg/msg/MultiStringTest.msg | 4 + .../msg/{AAAATest.msg => NestedMsgTest.msg} | 2 +- test_custom_msg/package.xml | 4 +- 31 files changed, 50 insertions(+), 636 deletions(-) delete mode 100644 actuator/CMakeLists.txt delete mode 100644 actuator/main.c delete mode 100644 actuator/package.xml delete mode 100644 altitude_sensor/CMakeLists.txt delete mode 100644 altitude_sensor/main.c delete mode 100644 altitude_sensor/package.xml delete mode 100644 control/CMakeLists.txt delete mode 100644 control/COLCON_IGNORE delete mode 100644 control/README.md delete mode 100644 control/main.cpp delete mode 100644 control/package.xml delete mode 100644 display/CMakeLists.txt delete mode 100644 display/main.c delete mode 100644 display/package.xml delete mode 100644 example_publisher_int32/CMakeLists.txt delete mode 100644 example_publisher_int32/main.c delete mode 100644 example_publisher_int32/package.xml delete mode 100644 example_subscriber_int32/CMakeLists.txt delete mode 100644 example_subscriber_int32/main.c delete mode 100644 example_subscriber_int32/package.xml delete mode 100644 test_custom_msg/COLCON_IGNORE create mode 100644 test_custom_msg/msg/MultiStringTest.msg rename test_custom_msg/msg/{AAAATest.msg => NestedMsgTest.msg} (88%) diff --git a/actuator/CMakeLists.txt b/actuator/CMakeLists.txt deleted file mode 100644 index 214832e..0000000 --- a/actuator/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(actuator) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) - -add_executable(actuator main.c) -ament_target_dependencies(actuator rclc std_msgs) - -install(TARGETS - actuator - DESTINATION lib/${PROJECT_NAME} -) - -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - -ament_package() diff --git a/actuator/main.c b/actuator/main.c deleted file mode 100644 index 96835bd..0000000 --- a/actuator/main.c +++ /dev/null @@ -1,61 +0,0 @@ -#include -#include -#include -#include - -#include - -static rclc_publisher_t* engine_pub; -static uint32_t engine_power = 100; - -void engine_on_message(const void* msgin) -{ - - const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; - - if (msg->data + engine_power > 0) - { - engine_power += msg->data; - } - else - { - engine_power = 0; - } - - // Publish new altitude - std_msgs__msg__UInt32 msg_out; - msg_out.data = engine_power; - rclc_publish(engine_pub, (const void*)&msg_out); -} - -int main(int argc, char* argv[]) -{ - (void)argc; - (void)argv; - - rclc_node_t* node = NULL; - rclc_subscription_t* engine_sub = NULL; - - - - rclc_init(0, NULL); - node = rclc_create_node("actuator", ""); - engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", engine_on_message, 1, false); - engine_pub = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", 1); - - // Publish new altitude - std_msgs__msg__UInt32 msg_out; - msg_out.data = engine_power; - rclc_publish(engine_pub, (const void*)&msg_out); - - rclc_spin_node(node); - - //if (altitude_sub) rclc_destroy_subscription(altitude_sub); - if (engine_sub) rclc_destroy_subscription(engine_sub); - if (engine_pub) rclc_destroy_publisher(engine_pub); - if (node) rclc_destroy_node(node); - - printf("Actuator node closed.\n"); - - return 0; -} diff --git a/actuator/package.xml b/actuator/package.xml deleted file mode 100644 index 391da4f..0000000 --- a/actuator/package.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - actuator - 0.0.1 - Demo. Actuator node - Javier Moreno - Apache License 2.0 - ament_cmake - rclc - std_msgs - - ament_cmake - - - diff --git a/altitude_sensor/CMakeLists.txt b/altitude_sensor/CMakeLists.txt deleted file mode 100644 index 6165086..0000000 --- a/altitude_sensor/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(altitude_sensor) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) - -add_executable(altitude_sensor main.c) -ament_target_dependencies(altitude_sensor rclc std_msgs) - -target_link_libraries(altitude_sensor m) - -install(TARGETS - altitude_sensor - DESTINATION lib/${PROJECT_NAME} -) - -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - -ament_package() diff --git a/altitude_sensor/main.c b/altitude_sensor/main.c deleted file mode 100644 index c4c4604..0000000 --- a/altitude_sensor/main.c +++ /dev/null @@ -1,74 +0,0 @@ -#include -#include -#include - -#include -#include -#include - - -static uint32_t Offset = 0; - -/** - * @brief - * - * @param msgin - */ -void on_power_message(const void* msgin) -{ - std_msgs__msg__UInt32* msg = (std_msgs__msg__UInt32*)msgin; - - Offset = msg->data; -} - - -/** - * @brief - * - * @param argc - * @param argv - * @return int - */ -int main(int argc, char *argv[]) -{ - (void)argc; - (void)argv; - rclc_init(0, NULL); - - rclc_node_t* node = NULL; - rclc_publisher_t* publisher = NULL; - rclc_subscription_t* power_subscription = NULL; - - - node = rclc_create_node("altitude_sensor", ""); - publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", 1); - //power_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", on_power_message, 1, false); - - double Altitude = 1000; - double Count = 0; - time_t t; - srand((unsigned) time(&t)); - - while (rclc_ok()) - { - Count += 0.1; - Altitude += (rand() % 10) * cos(Count); - - - // Publish new altitude - std_msgs__msg__Float64 msg; - msg.data = Altitude + Offset; - rclc_publish(publisher, (const void*)&msg); - - - // Spin node - rclc_spin_node_once(node, 1); - } - - if (publisher) rclc_destroy_publisher(publisher); - if (power_subscription) rclc_destroy_publisher(power_subscription); - if (node) rclc_destroy_node(node); - - printf("altitude sendor closed.\n"); - return 0; -} \ No newline at end of file diff --git a/altitude_sensor/package.xml b/altitude_sensor/package.xml deleted file mode 100644 index 547fcd9..0000000 --- a/altitude_sensor/package.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - altitude_sensor - 0.0.1 - Demo. Position sensor node - Javier Moreno - Apache License 2.0 - ament_cmake - rclc - std_msgs - - ament_cmake - - - diff --git a/control/CMakeLists.txt b/control/CMakeLists.txt deleted file mode 100644 index bb1aded..0000000 --- a/control/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(control) - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) - -add_executable(control main.cpp) -ament_target_dependencies(control rclcpp std_msgs) - -install(TARGETS - control - DESTINATION lib/${PROJECT_NAME} -) - -ament_package() diff --git a/control/COLCON_IGNORE b/control/COLCON_IGNORE deleted file mode 100644 index e69de29..0000000 diff --git a/control/README.md b/control/README.md deleted file mode 100644 index a8cdda4..0000000 --- a/control/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# Minimal publisher examples - -This package contains a few different strategies for creating short nodes which blast out messages. -The `talker_timer_lambda` and `talker_timer_member_function` recipes create subclasses of `rclcpp::Node` and set up an `rclcpp::timer` to periodically call functions which publish messages. -The `talker_without_subclass` recipe instead instantiates a `rclcpp::Node` object *without* subclassing it, which works, but is not compatible with composition, and thus is no longer the recommended style for ROS 2 coding. diff --git a/control/main.cpp b/control/main.cpp deleted file mode 100644 index 17d87f5..0000000 --- a/control/main.cpp +++ /dev/null @@ -1,83 +0,0 @@ -// Copyright 2016 Open Source Robotics Foundation, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/float64.hpp" -#include "std_msgs/msg/int32.hpp" -#include "std_msgs/msg/string.hpp" -using std::placeholders::_1; - -class ExternalNode : public rclcpp::Node -{ -public: - ExternalNode() : Node("control") - { - engine_power_publisher_ = this->create_publisher("std_msgs_msg_Int32"); - warn_publisher_ = this->create_publisher("std_msgs_msg_String"); - - altitude_subscription_ = this->create_subscription("std_msgs_msg_Float64", std::bind(&ExternalNode::topic_callback, this, _1)); - } - -private: - rclcpp::Publisher::SharedPtr engine_power_publisher_; - rclcpp::Publisher::SharedPtr warn_publisher_; - rclcpp::Subscription::SharedPtr altitude_subscription_; - - void topic_callback(const std_msgs::msg::Float64::SharedPtr msg) - { - // Warning - if (msg->data <= 500) - { - { - auto message = std_msgs::msg::String(); - message.data = "Failure!!"; - RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()) - this->warn_publisher_->publish(message); - } - - { - auto message = std_msgs::msg::Int32(); - message.data = 10; - this->engine_power_publisher_->publish(message); - } - - } - - // Failure - else if (msg->data <= 1000) - { - { - auto message = std_msgs::msg::String(); - message.data = "Warning!!"; - RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()) - this->warn_publisher_->publish(message); - } - - { - auto message = std_msgs::msg::Int32(); - message.data = 5; - this->engine_power_publisher_->publish(message); - } - - } - } -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} diff --git a/control/package.xml b/control/package.xml deleted file mode 100644 index e66e087..0000000 --- a/control/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - control - 0.0.1 - Demo. Node running on ros2 - Javier Moreno - Apache License 2.0 - Javier Moreno - - ament_cmake - - rclcpp - std_msgs - - rclcpp - std_msgs - - - ament_cmake - - - diff --git a/display/CMakeLists.txt b/display/CMakeLists.txt deleted file mode 100644 index 6671b2f..0000000 --- a/display/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(display) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) - -add_executable(display main.c) -ament_target_dependencies(display rclc std_msgs) - -install(TARGETS - display - DESTINATION lib/${PROJECT_NAME} -) - -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - -ament_package() diff --git a/display/main.c b/display/main.c deleted file mode 100644 index 7de14f9..0000000 --- a/display/main.c +++ /dev/null @@ -1,100 +0,0 @@ -#include -#include -#include -#include -#include - -#include - - -static float altitude; -static uint32_t engine_power; -static unsigned it; -static char Alert[200]; - -/** - * @brief Update screen - * - */ -void UpdateDisplay() -{ - printf("\r[received messages: %7u]\t [Altitude: %5.2f]\t [Engine power: %5u]\t [Status: %10s]\t\t\t", it++, altitude, engine_power, Alert); -} - - -/** - * @brief new alert callback - * - * @param msgin - */ -void on_alert_message(const void* msgin) -{ - const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; - strcpy(Alert, msg->data.data); - - UpdateDisplay(); -} - - -/** - * @brief new altitude calback - * - * @param msgin - */ -void on_altitude_message(const void* msgin) -{ - std_msgs__msg__Float64* msg = (std_msgs__msg__Float64*)msgin; - - altitude = msg->data; - UpdateDisplay(); -} - -/** - * @brief - * - * @param msgin - */ -void on_power_message(const void* msgin) -{ - std_msgs__msg__UInt32* msg = (std_msgs__msg__UInt32*)msgin; - - engine_power = msg->data; - UpdateDisplay(); -} - - -/** - * @brief Main - * - * @param argc - * @param argv - * @return int - */ -int main(int argc, char *argv[]) -{ - (void)argc; - (void)argv; - - rclc_node_t* node = NULL; - rclc_subscription_t* alert_subscription = NULL; - rclc_subscription_t* altitude_subscription = NULL; - rclc_subscription_t* power_subscription = NULL; - - - rclc_init(0, NULL); - - node = rclc_create_node("display", ""); - - alert_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_alert_message, 1, false); - altitude_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", on_altitude_message, 1, false); - power_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", on_power_message, 1, false); - - rclc_spin_node(node); - - if (alert_subscription) rclc_destroy_subscription(alert_subscription); - if (altitude_subscription) rclc_destroy_subscription(altitude_subscription); - if (node) rclc_destroy_node(node); - - printf("Display node closed."); - -} \ No newline at end of file diff --git a/display/package.xml b/display/package.xml deleted file mode 100644 index 20fb8d5..0000000 --- a/display/package.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - display - 0.0.1 - Demo. Display on screen any message - Javier Moreno - Apache License 2.0 - ament_cmake - rclc - std_msgs - - ament_cmake - - - diff --git a/example_publisher/CMakeLists.txt b/example_publisher/CMakeLists.txt index 6f45c4f..6a3bc99 100644 --- a/example_publisher/CMakeLists.txt +++ b/example_publisher/CMakeLists.txt @@ -5,9 +5,10 @@ project(example_publisher) find_package(ament_cmake REQUIRED) find_package(rclc REQUIRED) find_package(std_msgs REQUIRED) +find_package(example_custom_msgs REQUIRED) add_executable(example_publisher main.c) -ament_target_dependencies(example_publisher rclc std_msgs) +ament_target_dependencies(example_publisher rclc std_msgs example_custom_msgs) install(TARGETS example_publisher diff --git a/example_publisher/main.c b/example_publisher/main.c index 5624e3a..d31bc7d 100644 --- a/example_publisher/main.c +++ b/example_publisher/main.c @@ -1,5 +1,5 @@ #include -#include +#include #include @@ -10,22 +10,41 @@ int main(int argc, char* argv[]) rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("publisher_node", ""); rclc_publisher_t* publisher = - rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "publisher_example", 1); + rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(example_custom_msgs, msg, NestedMsgTest), "example_custom_msgs_msg_NestedMsgTest", 1); - std_msgs__msg__String msg; - char buff[128] = {0}; - msg.data.data = buff; - msg.data.capacity = sizeof(buff); - msg.data.size = 0; + example_custom_msgs__msg__NestedMsgTest msg; + char Buff1[30]; + msg.data14.data1.data = Buff1; + msg.data14.data1.size = 0; + msg.data14.data1.capacity = sizeof(Buff1); + + char Buff2[30]; + msg.data14.data2.data = Buff2; + msg.data14.data2.size = 0; + msg.data14.data2.capacity = sizeof(Buff1); + + char Buff3[30]; + msg.data14.data3.data = Buff3; + msg.data14.data3.size = 0; + msg.data14.data3.capacity = sizeof(Buff1); + + char Buff4[30]; + msg.data14.data4.data = Buff4; + msg.data14.data4.size = 0; + msg.data14.data4.capacity = sizeof(Buff1); + + int num = 0; while (rclc_ok()) { - msg.data.size = snprintf(msg.data.data, msg.data.capacity, "Hello World %i", num++); - if (msg.data.size > msg.data.capacity) - msg.data.size = 0; + msg.data14.data1.size = snprintf(msg.data14.data1.data, msg.data14.data1.capacity, "1 - %i", num++); + msg.data14.data2.size = snprintf(msg.data14.data2.data, msg.data14.data2.capacity, "2 - %i", num++); + msg.data14.data3.size = snprintf(msg.data14.data3.data, msg.data14.data3.capacity, "3 - %i", num++); + msg.data14.data4.size = snprintf(msg.data14.data4.data, msg.data14.data4.capacity, "4 - %i", num++); + - printf("Sending: '%s'\n", msg.data.data); + printf("Sending (%i): '%s\t%s\t%s\t%s'\n", sizeof(msg), msg.data14.data1.data, msg.data14.data2.data, msg.data14.data3.data, msg.data14.data4.data); rclc_publish(publisher, (const void*)&msg); rclc_spin_node_once(node, 500); } diff --git a/example_publisher/package.xml b/example_publisher/package.xml index 5406617..71329f7 100644 --- a/example_publisher/package.xml +++ b/example_publisher/package.xml @@ -9,6 +9,7 @@ ament_cmake rclc std_msgs + example_custom_msgs ament_cmake diff --git a/example_publisher_int32/CMakeLists.txt b/example_publisher_int32/CMakeLists.txt deleted file mode 100644 index e6036d5..0000000 --- a/example_publisher_int32/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(example_publisher_int32) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) - -add_executable(example_publisher_int32 main.c) -ament_target_dependencies(example_publisher_int32 rclc std_msgs) - -install(TARGETS - example_publisher_int32 - DESTINATION lib/${PROJECT_NAME} -) - -ament_package() diff --git a/example_publisher_int32/main.c b/example_publisher_int32/main.c deleted file mode 100644 index 4eef187..0000000 --- a/example_publisher_int32/main.c +++ /dev/null @@ -1,44 +0,0 @@ -#include -#include - -#include - -int main(int argc, char *argv[]) -{ - (void)argc; - (void)argv; - - rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("publisher_node", ""); - rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", 1); - - std_msgs__msg__Int32 msg; - msg.data = -1; - - while (rclc_ok()) - { - printf("Sending: '%i'\n", msg.data++); - rclc_publish(publisher, (const void*)&msg); - for (unsigned i=0; i < 999999; i++){} - rclc_spin_node_once(node, 1000); - } - - if (publisher) - { - rclc_destroy_publisher(publisher); - } - else - { - printf("Create publisher error\n"); - } - - if (node) - { - rclc_destroy_node(node); - } - else - { - printf("Create node error\n"); - } - return 0; -} \ No newline at end of file diff --git a/example_publisher_int32/package.xml b/example_publisher_int32/package.xml deleted file mode 100644 index 4cb8206..0000000 --- a/example_publisher_int32/package.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - example_publisher_int32 - 0.0.1 - Example of a publisher using int32 - borjaouterelo - Apache License 2.0 - ament_cmake - rclc - std_msgs - - ament_cmake - - - diff --git a/example_subscriber/CMakeLists.txt b/example_subscriber/CMakeLists.txt index 3b0d23e..682298c 100644 --- a/example_subscriber/CMakeLists.txt +++ b/example_subscriber/CMakeLists.txt @@ -5,9 +5,10 @@ project(example_subscriber) find_package(ament_cmake REQUIRED) find_package(rclc REQUIRED) find_package(std_msgs REQUIRED) +find_package(example_custom_msgs REQUIRED) add_executable(example_subscriber main.c) -ament_target_dependencies(example_subscriber rclc std_msgs) +ament_target_dependencies(example_subscriber rclc std_msgs example_custom_msgs) install(TARGETS example_subscriber diff --git a/example_subscriber/main.c b/example_subscriber/main.c index db9b019..328d308 100644 --- a/example_subscriber/main.c +++ b/example_subscriber/main.c @@ -1,12 +1,12 @@ #include -#include +#include #include void on_message(const void* msgin) { - const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; - printf("I heard: [%s]\n", msg->data.data); + const example_custom_msgs__msg__NestedMsgTest* msg = (const example_custom_msgs__msg__NestedMsgTest*)msgin; + printf("I heard: [%s\t%s\t%s\t%s]\n", msg->data14.data1.data, msg->data14.data2.data, msg->data14.data3.data, msg->data14.data4.data); } int main(int argc, char* argv[]) @@ -15,8 +15,7 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("subscription_node", ""); - rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), - "subscription_example", on_message, 1, false); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(example_custom_msgs, msg, NestedMsgTest), "example_custom_msgs_msg_NestedMsgTest", on_message, 1, false); rclc_spin_node(node); diff --git a/example_subscriber/package.xml b/example_subscriber/package.xml index ffdcfd8..0a988d5 100644 --- a/example_subscriber/package.xml +++ b/example_subscriber/package.xml @@ -9,6 +9,7 @@ ament_cmake rclc std_msgs + example_custom_msgs ament_cmake diff --git a/example_subscriber_int32/CMakeLists.txt b/example_subscriber_int32/CMakeLists.txt deleted file mode 100644 index 7675a04..0000000 --- a/example_subscriber_int32/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(example_subscriber_int32) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) - -add_executable(example_subscriber_int32 main.c) -ament_target_dependencies(example_subscriber_int32 rclc std_msgs) - -install(TARGETS - example_subscriber_int32 - DESTINATION lib/${PROJECT_NAME} -) - -ament_package() diff --git a/example_subscriber_int32/main.c b/example_subscriber_int32/main.c deleted file mode 100644 index 0f7816b..0000000 --- a/example_subscriber_int32/main.c +++ /dev/null @@ -1,25 +0,0 @@ -#include -#include - -#include - -void on_message(const void* msgin) -{ - const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; - printf("I heard: [%i]\n", msg->data); -} - -int main(int argc, char* argv[]) -{ - (void)argc; - (void)argv; - rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("subscription_node", ""); - rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", on_message, 1, false); - - rclc_spin_node(node); - - rclc_destroy_subscription(sub); - rclc_destroy_node(node); - return 0; -} diff --git a/example_subscriber_int32/package.xml b/example_subscriber_int32/package.xml deleted file mode 100644 index e66c894..0000000 --- a/example_subscriber_int32/package.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - example_subscriber_int32 - 0.0.1 - Example of a subscriber using int32 - borjaouterelo - Apache License 2.0 - ament_cmake - rclc - std_msgs - - ament_cmake - - - diff --git a/test_custom_msg/CMakeLists.txt b/test_custom_msg/CMakeLists.txt index 07d75d3..95f154e 100644 --- a/test_custom_msg/CMakeLists.txt +++ b/test_custom_msg/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(test_custom_msg) +project(example_custom_msgs) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -17,7 +17,8 @@ find_package(builtin_interfaces REQUIRED) find_package(rosidl_default_generators REQUIRED) set(msg_files - "msg/AAAATest.msg" + "msg/MultiStringTest.msg" + "msg/NestedMsgTest.msg" ) rosidl_generate_interfaces(${PROJECT_NAME} ${msg_files} diff --git a/test_custom_msg/COLCON_IGNORE b/test_custom_msg/COLCON_IGNORE deleted file mode 100644 index e69de29..0000000 diff --git a/test_custom_msg/msg/MultiStringTest.msg b/test_custom_msg/msg/MultiStringTest.msg new file mode 100644 index 0000000..6ce445c --- /dev/null +++ b/test_custom_msg/msg/MultiStringTest.msg @@ -0,0 +1,4 @@ +string data1 +string data2 +string data3 +string data4 \ No newline at end of file diff --git a/test_custom_msg/msg/AAAATest.msg b/test_custom_msg/msg/NestedMsgTest.msg similarity index 88% rename from test_custom_msg/msg/AAAATest.msg rename to test_custom_msg/msg/NestedMsgTest.msg index 9531426..3bc31ad 100644 --- a/test_custom_msg/msg/AAAATest.msg +++ b/test_custom_msg/msg/NestedMsgTest.msg @@ -11,4 +11,4 @@ int32 data10 uint32 data11 int64 data12 uint64 data13 -string data14 \ No newline at end of file +MultiStringTest data14 \ No newline at end of file diff --git a/test_custom_msg/package.xml b/test_custom_msg/package.xml index 65565e3..ea83a3a 100644 --- a/test_custom_msg/package.xml +++ b/test_custom_msg/package.xml @@ -1,8 +1,8 @@ - test_custom_msg - 0.5.0 + example_custom_msgs + 1.0.0 Custom generated msg. Javier Moreno Apache License 2.0 From 462c219d2bd4310c1d93a0fa07a1eca6bb5fe3fe Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Fri, 28 Sep 2018 09:57:29 +0200 Subject: [PATCH 10/27] Change examples in order to be more explanatory --- example_publisher/main.c | 44 ++++++++++++++++++++++++++++++++++----- example_subscriber/main.c | 21 ++++++++++++++++++- 2 files changed, 59 insertions(+), 6 deletions(-) diff --git a/example_publisher/main.c b/example_publisher/main.c index d31bc7d..e72c908 100644 --- a/example_publisher/main.c +++ b/example_publisher/main.c @@ -38,13 +38,47 @@ int main(int argc, char* argv[]) int num = 0; while (rclc_ok()) { - msg.data14.data1.size = snprintf(msg.data14.data1.data, msg.data14.data1.capacity, "1 - %i", num++); - msg.data14.data2.size = snprintf(msg.data14.data2.data, msg.data14.data2.capacity, "2 - %i", num++); - msg.data14.data3.size = snprintf(msg.data14.data3.data, msg.data14.data3.capacity, "3 - %i", num++); - msg.data14.data4.size = snprintf(msg.data14.data4.data, msg.data14.data4.capacity, "4 - %i", num++); + msg.data1 = (bool)(num & 0x01); + msg.data2 = (uint8_t)num; + msg.data3 = (signed char)num; + msg.data4 = (float)num; + msg.data5 = (double)num; + msg.data6 = (int8_t)num; + msg.data7 = (uint8_t)num; + msg.data8 = (int16_t)num; + msg.data9 = (uint16_t)num; + msg.data10 = (int32_t)num; + msg.data11 = (uint32_t)num; + msg.data12 = (int64_t)num; + msg.data13 = (uint64_t)num; + msg.data14.data1.size = snprintf(msg.data14.data1.data, msg.data14.data1.capacity, "Msg A - %i", num); + msg.data14.data2.size = snprintf(msg.data14.data2.data, msg.data14.data2.capacity, "Msg B - %i", num); + msg.data14.data3.size = snprintf(msg.data14.data3.data, msg.data14.data3.capacity, "Msg C - %i", num); + msg.data14.data4.size = snprintf(msg.data14.data4.data, msg.data14.data4.capacity, "Msg D - %i", num); + num++; - printf("Sending (%i): '%s\t%s\t%s\t%s'\n", sizeof(msg), msg.data14.data1.data, msg.data14.data2.data, msg.data14.data3.data, msg.data14.data4.data); + printf("I send:\n"); + printf("\tBool: %u\n", msg.data1); + printf("\tuint8_t: %u\n", msg.data2); + printf("\tsigned char: %u\n", msg.data3); + printf("\tfloat: %f\n", msg.data4); + printf("\tdouble: %lf\n", msg.data5); + printf("\tint8_t: %i\n", msg.data6); + printf("\tuint8_t: %u\n", msg.data7); + printf("\tint16_t: %i\n", msg.data8); + printf("\tuint16_t: %u\n", msg.data9); + printf("\tint32_t: %i\n", msg.data10); + printf("\tuint32_t: %u\n", msg.data11); + printf("\tint64_t: %li\n", msg.data12); + printf("\tuint64_t: %lu\n", msg.data13); + + printf("\tstring 1: %s\n", msg.data14.data1.data); + printf("\tstring 2: %s\n", msg.data14.data2.data); + printf("\tstring 3: %s\n", msg.data14.data3.data); + printf("\tstring 4: %s\n", msg.data14.data4.data); + printf("\n\n"); + rclc_publish(publisher, (const void*)&msg); rclc_spin_node_once(node, 500); } diff --git a/example_subscriber/main.c b/example_subscriber/main.c index 328d308..49beaea 100644 --- a/example_subscriber/main.c +++ b/example_subscriber/main.c @@ -6,7 +6,26 @@ void on_message(const void* msgin) { const example_custom_msgs__msg__NestedMsgTest* msg = (const example_custom_msgs__msg__NestedMsgTest*)msgin; - printf("I heard: [%s\t%s\t%s\t%s]\n", msg->data14.data1.data, msg->data14.data2.data, msg->data14.data3.data, msg->data14.data4.data); + printf("I heard:\n"); + printf("\tBool: %u\n", msg->data1); + printf("\tuint8_t: %u\n", msg->data2); + printf("\tsigned char: %u\n", msg->data3); + printf("\tfloat: %f\n", msg->data4); + printf("\tdouble: %lf\n", msg->data5); + printf("\tint8_t: %i\n", msg->data6); + printf("\tuint8_t: %u\n", msg->data7); + printf("\tint16_t: %i\n", msg->data8); + printf("\tuint16_t: %u\n", msg->data9); + printf("\tint32_t: %i\n", msg->data10); + printf("\tuint32_t: %u\n", msg->data11); + printf("\tint64_t: %li\n", msg->data12); + printf("\tuint64_t: %lu\n", msg->data13); + + printf("\tstring 1: %s\n", msg->data14.data1.data); + printf("\tstring 2: %s\n", msg->data14.data2.data); + printf("\tstring 3: %s\n", msg->data14.data3.data); + printf("\tstring 4: %s\n", msg->data14.data4.data); + printf("\n\n"); } int main(int argc, char* argv[]) From 1d923df8054ceb323450f7199eb92e868a4d2afd Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Thu, 4 Oct 2018 10:29:52 +0200 Subject: [PATCH 11/27] Added complex examples and RAD0 ros2 node --- RAD0_control/CMakeLists.txt | 33 ++++++++ RAD0_control/README.md | 5 ++ RAD0_control/main.cpp | 83 +++++++++++++++++++ RAD0_control/package.xml | 23 +++++ .../CMakeLists.txt | 2 +- .../msg/MultiStringTest.msg | 0 .../msg/NestedMsgTest.msg | 0 {test_custom_msg => complex_msg}/package.xml | 4 +- complex_msg_publisher/CMakeLists.txt | 27 ++++++ .../main.c | 6 +- .../package.xml | 9 +- complex_msg_subscriber/CMakeLists.txt | 25 ++++++ .../main.c | 6 +- .../package.xml | 9 +- example_publisher/CMakeLists.txt | 20 ----- example_subscriber/CMakeLists.txt | 20 ----- 16 files changed, 213 insertions(+), 59 deletions(-) create mode 100644 RAD0_control/CMakeLists.txt create mode 100644 RAD0_control/README.md create mode 100644 RAD0_control/main.cpp create mode 100644 RAD0_control/package.xml rename {test_custom_msg => complex_msg}/CMakeLists.txt (96%) rename {test_custom_msg => complex_msg}/msg/MultiStringTest.msg (100%) rename {test_custom_msg => complex_msg}/msg/NestedMsgTest.msg (100%) rename {test_custom_msg => complex_msg}/package.xml (89%) create mode 100644 complex_msg_publisher/CMakeLists.txt rename {example_publisher => complex_msg_publisher}/main.c (91%) rename {example_publisher => complex_msg_publisher}/package.xml (60%) create mode 100644 complex_msg_subscriber/CMakeLists.txt rename {example_subscriber => complex_msg_subscriber}/main.c (81%) rename {example_subscriber => complex_msg_subscriber}/package.xml (60%) delete mode 100644 example_publisher/CMakeLists.txt delete mode 100644 example_subscriber/CMakeLists.txt diff --git a/RAD0_control/CMakeLists.txt b/RAD0_control/CMakeLists.txt new file mode 100644 index 0000000..eb56335 --- /dev/null +++ b/RAD0_control/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 3.5) +project(rad0_control) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(std_msgs REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/RAD0_control/README.md b/RAD0_control/README.md new file mode 100644 index 0000000..a8cdda4 --- /dev/null +++ b/RAD0_control/README.md @@ -0,0 +1,5 @@ +# Minimal publisher examples + +This package contains a few different strategies for creating short nodes which blast out messages. +The `talker_timer_lambda` and `talker_timer_member_function` recipes create subclasses of `rclcpp::Node` and set up an `rclcpp::timer` to periodically call functions which publish messages. +The `talker_without_subclass` recipe instead instantiates a `rclcpp::Node` object *without* subclassing it, which works, but is not compatible with composition, and thus is no longer the recommended style for ROS 2 coding. diff --git a/RAD0_control/main.cpp b/RAD0_control/main.cpp new file mode 100644 index 0000000..17d87f5 --- /dev/null +++ b/RAD0_control/main.cpp @@ -0,0 +1,83 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/float64.hpp" +#include "std_msgs/msg/int32.hpp" +#include "std_msgs/msg/string.hpp" +using std::placeholders::_1; + +class ExternalNode : public rclcpp::Node +{ +public: + ExternalNode() : Node("control") + { + engine_power_publisher_ = this->create_publisher("std_msgs_msg_Int32"); + warn_publisher_ = this->create_publisher("std_msgs_msg_String"); + + altitude_subscription_ = this->create_subscription("std_msgs_msg_Float64", std::bind(&ExternalNode::topic_callback, this, _1)); + } + +private: + rclcpp::Publisher::SharedPtr engine_power_publisher_; + rclcpp::Publisher::SharedPtr warn_publisher_; + rclcpp::Subscription::SharedPtr altitude_subscription_; + + void topic_callback(const std_msgs::msg::Float64::SharedPtr msg) + { + // Warning + if (msg->data <= 500) + { + { + auto message = std_msgs::msg::String(); + message.data = "Failure!!"; + RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()) + this->warn_publisher_->publish(message); + } + + { + auto message = std_msgs::msg::Int32(); + message.data = 10; + this->engine_power_publisher_->publish(message); + } + + } + + // Failure + else if (msg->data <= 1000) + { + { + auto message = std_msgs::msg::String(); + message.data = "Warning!!"; + RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()) + this->warn_publisher_->publish(message); + } + + { + auto message = std_msgs::msg::Int32(); + message.data = 5; + this->engine_power_publisher_->publish(message); + } + + } + } +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/RAD0_control/package.xml b/RAD0_control/package.xml new file mode 100644 index 0000000..7479744 --- /dev/null +++ b/RAD0_control/package.xml @@ -0,0 +1,23 @@ + + + + rad0_control + 0.0.1 + Real apliacion demostration. + Javier Moreno + Apache License 2.0 + Javier Moreno + + ament_cmake + + rclcpp + std_msgs + + rclcpp + std_msgs + + + ament_cmake + + + diff --git a/test_custom_msg/CMakeLists.txt b/complex_msg/CMakeLists.txt similarity index 96% rename from test_custom_msg/CMakeLists.txt rename to complex_msg/CMakeLists.txt index 95f154e..d975c3d 100644 --- a/test_custom_msg/CMakeLists.txt +++ b/complex_msg/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(example_custom_msgs) +project(complex_msgs) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) diff --git a/test_custom_msg/msg/MultiStringTest.msg b/complex_msg/msg/MultiStringTest.msg similarity index 100% rename from test_custom_msg/msg/MultiStringTest.msg rename to complex_msg/msg/MultiStringTest.msg diff --git a/test_custom_msg/msg/NestedMsgTest.msg b/complex_msg/msg/NestedMsgTest.msg similarity index 100% rename from test_custom_msg/msg/NestedMsgTest.msg rename to complex_msg/msg/NestedMsgTest.msg diff --git a/test_custom_msg/package.xml b/complex_msg/package.xml similarity index 89% rename from test_custom_msg/package.xml rename to complex_msg/package.xml index ea83a3a..5f32a6f 100644 --- a/test_custom_msg/package.xml +++ b/complex_msg/package.xml @@ -1,9 +1,9 @@ - example_custom_msgs + complex_msgs 1.0.0 - Custom generated msg. + Example of a complex msg. Javier Moreno Apache License 2.0 diff --git a/complex_msg_publisher/CMakeLists.txt b/complex_msg_publisher/CMakeLists.txt new file mode 100644 index 0000000..95bb495 --- /dev/null +++ b/complex_msg_publisher/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(complex_msg_publisher) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(complex_msgs REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc complex_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + +ament_package() diff --git a/example_publisher/main.c b/complex_msg_publisher/main.c similarity index 91% rename from example_publisher/main.c rename to complex_msg_publisher/main.c index e72c908..c0fefe1 100644 --- a/example_publisher/main.c +++ b/complex_msg_publisher/main.c @@ -1,5 +1,5 @@ #include -#include +#include #include @@ -10,9 +10,9 @@ int main(int argc, char* argv[]) rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("publisher_node", ""); rclc_publisher_t* publisher = - rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(example_custom_msgs, msg, NestedMsgTest), "example_custom_msgs_msg_NestedMsgTest", 1); + rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(complex_msgs, msg, NestedMsgTest), "complex_msgs_msg_NestedMsgTest", 1); - example_custom_msgs__msg__NestedMsgTest msg; + complex_msgs__msg__NestedMsgTest msg; char Buff1[30]; msg.data14.data1.data = Buff1; msg.data14.data1.size = 0; diff --git a/example_publisher/package.xml b/complex_msg_publisher/package.xml similarity index 60% rename from example_publisher/package.xml rename to complex_msg_publisher/package.xml index 71329f7..84d7bf0 100644 --- a/example_publisher/package.xml +++ b/complex_msg_publisher/package.xml @@ -1,15 +1,14 @@ - example_publisher + complex_msg_publisher 0.0.1 - Example of a publisher - borjaouterelo + Example of a complex msg publisher + Javier Moreno Apache License 2.0 ament_cmake rclc - std_msgs - example_custom_msgs + complex_msgs ament_cmake diff --git a/complex_msg_subscriber/CMakeLists.txt b/complex_msg_subscriber/CMakeLists.txt new file mode 100644 index 0000000..f4f846e --- /dev/null +++ b/complex_msg_subscriber/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(complex_msg_subscriber) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(complex_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc complex_msgs) + +install(TARGETS +${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + +ament_package() diff --git a/example_subscriber/main.c b/complex_msg_subscriber/main.c similarity index 81% rename from example_subscriber/main.c rename to complex_msg_subscriber/main.c index 49beaea..4a6d6a5 100644 --- a/example_subscriber/main.c +++ b/complex_msg_subscriber/main.c @@ -1,11 +1,11 @@ #include -#include +#include #include void on_message(const void* msgin) { - const example_custom_msgs__msg__NestedMsgTest* msg = (const example_custom_msgs__msg__NestedMsgTest*)msgin; + const complex_msgs__msg__NestedMsgTest* msg = (const complex_msgs__msg__NestedMsgTest*)msgin; printf("I heard:\n"); printf("\tBool: %u\n", msg->data1); printf("\tuint8_t: %u\n", msg->data2); @@ -34,7 +34,7 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("subscription_node", ""); - rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(example_custom_msgs, msg, NestedMsgTest), "example_custom_msgs_msg_NestedMsgTest", on_message, 1, false); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(complex_msgs, msg, NestedMsgTest), "complex_msgs_msg_NestedMsgTest", on_message, 1, false); rclc_spin_node(node); diff --git a/example_subscriber/package.xml b/complex_msg_subscriber/package.xml similarity index 60% rename from example_subscriber/package.xml rename to complex_msg_subscriber/package.xml index 0a988d5..59f8ec9 100644 --- a/example_subscriber/package.xml +++ b/complex_msg_subscriber/package.xml @@ -1,15 +1,14 @@ - example_subscriber + complex_msg_subscriber 0.0.1 - Example of a subscriber - borjaouterelo + Example of a complex smg subcriber + Javier Moreno Apache License 2.0 ament_cmake rclc - std_msgs - example_custom_msgs + complex_msgs ament_cmake diff --git a/example_publisher/CMakeLists.txt b/example_publisher/CMakeLists.txt deleted file mode 100644 index 6a3bc99..0000000 --- a/example_publisher/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(example_publisher) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) -find_package(example_custom_msgs REQUIRED) - -add_executable(example_publisher main.c) -ament_target_dependencies(example_publisher rclc std_msgs example_custom_msgs) - -install(TARGETS - example_publisher - DESTINATION lib/${PROJECT_NAME} -) - -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - -ament_package() diff --git a/example_subscriber/CMakeLists.txt b/example_subscriber/CMakeLists.txt deleted file mode 100644 index 682298c..0000000 --- a/example_subscriber/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(example_subscriber) - -find_package(ament_cmake REQUIRED) -find_package(rclc REQUIRED) -find_package(std_msgs REQUIRED) -find_package(example_custom_msgs REQUIRED) - -add_executable(example_subscriber main.c) -ament_target_dependencies(example_subscriber rclc std_msgs example_custom_msgs) - -install(TARGETS - example_subscriber - DESTINATION lib/${PROJECT_NAME} -) - -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - -ament_package() From 680a706ad91a2b2e1fe910bd7969b0ff5c9889f1 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Thu, 4 Oct 2018 10:40:12 +0200 Subject: [PATCH 12/27] Added real aplications demos --- RAD0_actuator/CMakeLists.txt | 25 +++++++ RAD0_actuator/main.c | 61 +++++++++++++++++ RAD0_actuator/package.xml | 16 +++++ RAD0_altitude_sensor/CMakeLists.txt | 27 ++++++++ RAD0_altitude_sensor/main.c | 53 +++++++++++++++ RAD0_altitude_sensor/package.xml | 16 +++++ RAD0_display/CMakeLists.txt | 25 +++++++ RAD0_display/main.c | 100 ++++++++++++++++++++++++++++ RAD0_display/package.xml | 16 +++++ 9 files changed, 339 insertions(+) create mode 100644 RAD0_actuator/CMakeLists.txt create mode 100644 RAD0_actuator/main.c create mode 100644 RAD0_actuator/package.xml create mode 100644 RAD0_altitude_sensor/CMakeLists.txt create mode 100644 RAD0_altitude_sensor/main.c create mode 100644 RAD0_altitude_sensor/package.xml create mode 100644 RAD0_display/CMakeLists.txt create mode 100644 RAD0_display/main.c create mode 100644 RAD0_display/package.xml diff --git a/RAD0_actuator/CMakeLists.txt b/RAD0_actuator/CMakeLists.txt new file mode 100644 index 0000000..3d023b8 --- /dev/null +++ b/RAD0_actuator/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(rad0_actuator) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + +ament_package() diff --git a/RAD0_actuator/main.c b/RAD0_actuator/main.c new file mode 100644 index 0000000..96835bd --- /dev/null +++ b/RAD0_actuator/main.c @@ -0,0 +1,61 @@ +#include +#include +#include +#include + +#include + +static rclc_publisher_t* engine_pub; +static uint32_t engine_power = 100; + +void engine_on_message(const void* msgin) +{ + + const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; + + if (msg->data + engine_power > 0) + { + engine_power += msg->data; + } + else + { + engine_power = 0; + } + + // Publish new altitude + std_msgs__msg__UInt32 msg_out; + msg_out.data = engine_power; + rclc_publish(engine_pub, (const void*)&msg_out); +} + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + + rclc_node_t* node = NULL; + rclc_subscription_t* engine_sub = NULL; + + + + rclc_init(0, NULL); + node = rclc_create_node("actuator", ""); + engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", engine_on_message, 1, false); + engine_pub = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", 1); + + // Publish new altitude + std_msgs__msg__UInt32 msg_out; + msg_out.data = engine_power; + rclc_publish(engine_pub, (const void*)&msg_out); + + rclc_spin_node(node); + + //if (altitude_sub) rclc_destroy_subscription(altitude_sub); + if (engine_sub) rclc_destroy_subscription(engine_sub); + if (engine_pub) rclc_destroy_publisher(engine_pub); + if (node) rclc_destroy_node(node); + + printf("Actuator node closed.\n"); + + return 0; +} diff --git a/RAD0_actuator/package.xml b/RAD0_actuator/package.xml new file mode 100644 index 0000000..6de1f09 --- /dev/null +++ b/RAD0_actuator/package.xml @@ -0,0 +1,16 @@ + + + + rad0_actuator + 0.0.1 + Real apliacion demostration. Actuator node + Javier Moreno + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/RAD0_altitude_sensor/CMakeLists.txt b/RAD0_altitude_sensor/CMakeLists.txt new file mode 100644 index 0000000..1978528 --- /dev/null +++ b/RAD0_altitude_sensor/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(rad0_altitude_sensor) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +target_link_libraries(${PROJECT_NAME} m) + +install(TARGETS +${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + +ament_package() diff --git a/RAD0_altitude_sensor/main.c b/RAD0_altitude_sensor/main.c new file mode 100644 index 0000000..891f03b --- /dev/null +++ b/RAD0_altitude_sensor/main.c @@ -0,0 +1,53 @@ +#include +#include +#include + +#include +#include +#include + + + +/** + * @brief + * + * @param argc + * @param argv + * @return int + */ +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + + rclc_node_t* node = NULL; + rclc_publisher_t* publisher = NULL; + + node = rclc_create_node("altitude_sensor", ""); + publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", 1); + + + double A = 0; + + + while (rclc_ok()) + { + A += 0.0001; + + // Publish new altitude + std_msgs__msg__Float64 msg; + msg.data = 500 * sin(A) + 950; + rclc_publish(publisher, (const void*)&msg); + + + // Spin node + rclc_spin_node_once(node, 0); + } + + if (publisher) rclc_destroy_publisher(publisher); + if (node) rclc_destroy_node(node); + + printf("altitude sendor closed.\n"); + return 0; +} \ No newline at end of file diff --git a/RAD0_altitude_sensor/package.xml b/RAD0_altitude_sensor/package.xml new file mode 100644 index 0000000..60aac8e --- /dev/null +++ b/RAD0_altitude_sensor/package.xml @@ -0,0 +1,16 @@ + + + + rad0_altitude_sensor + 0.0.1 + Real apliacion demostration. Position sensor node + Javier Moreno + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/RAD0_display/CMakeLists.txt b/RAD0_display/CMakeLists.txt new file mode 100644 index 0000000..8fadc51 --- /dev/null +++ b/RAD0_display/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(rad0_display) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +install(TARGETS +${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) + +ament_package() diff --git a/RAD0_display/main.c b/RAD0_display/main.c new file mode 100644 index 0000000..0d14c86 --- /dev/null +++ b/RAD0_display/main.c @@ -0,0 +1,100 @@ +#include +#include +#include +#include +#include + +#include + + +static float altitude; +static uint32_t engine_power; +static unsigned it; +static char Alert[200]; + +/** + * @brief Update screen + * + */ +void UpdateDisplay() +{ + printf("\r[received messages: %7u] [Altitude: %8.2f] [Engine power: %8u] [Status: %10s]", it++, altitude, engine_power, Alert); +} + + +/** + * @brief new alert callback + * + * @param msgin + */ +void on_alert_message(const void* msgin) +{ + const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; + strcpy(Alert, msg->data.data); + + UpdateDisplay(); +} + + +/** + * @brief new altitude calback + * + * @param msgin + */ +void on_altitude_message(const void* msgin) +{ + std_msgs__msg__Float64* msg = (std_msgs__msg__Float64*)msgin; + + altitude = msg->data; + UpdateDisplay(); +} + +/** + * @brief + * + * @param msgin + */ +void on_power_message(const void* msgin) +{ + std_msgs__msg__UInt32* msg = (std_msgs__msg__UInt32*)msgin; + + engine_power = msg->data; + UpdateDisplay(); +} + + +/** + * @brief Main + * + * @param argc + * @param argv + * @return int + */ +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + + rclc_node_t* node = NULL; + rclc_subscription_t* alert_subscription = NULL; + rclc_subscription_t* altitude_subscription = NULL; + rclc_subscription_t* power_subscription = NULL; + + + rclc_init(0, NULL); + + node = rclc_create_node("display", ""); + + alert_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_alert_message, 1, false); + altitude_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", on_altitude_message, 1, false); + power_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", on_power_message, 1, false); + + rclc_spin_node(node); + + if (alert_subscription) rclc_destroy_subscription(alert_subscription); + if (altitude_subscription) rclc_destroy_subscription(altitude_subscription); + if (node) rclc_destroy_node(node); + + printf("Display node closed."); + +} \ No newline at end of file diff --git a/RAD0_display/package.xml b/RAD0_display/package.xml new file mode 100644 index 0000000..b81b163 --- /dev/null +++ b/RAD0_display/package.xml @@ -0,0 +1,16 @@ + + + + rad0_display + 0.0.1 + Real apliacion demostration. Display on screen any message + Javier Moreno + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + From 581d0bd8982ed569f620c3e2939136f51aabb5f6 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Thu, 4 Oct 2018 10:51:13 +0200 Subject: [PATCH 13/27] Added common demos --- int32_publisher/CMakeLists.txt | 23 +++++++++++++++++++++ int32_publisher/main.c | 26 ++++++++++++++++++++++++ int32_publisher/package.xml | 16 +++++++++++++++ int32_subscriber/CMakeLists.txt | 23 +++++++++++++++++++++ int32_subscriber/main.c | 26 ++++++++++++++++++++++++ int32_subscriber/package.xml | 16 +++++++++++++++ string_publisher/CMakeLists.txt | 23 +++++++++++++++++++++ string_publisher/main.c | 35 ++++++++++++++++++++++++++++++++ string_publisher/package.xml | 16 +++++++++++++++ string_subscriber/CMakeLists.txt | 23 +++++++++++++++++++++ string_subscriber/main.c | 26 ++++++++++++++++++++++++ string_subscriber/package.xml | 16 +++++++++++++++ 12 files changed, 269 insertions(+) create mode 100644 int32_publisher/CMakeLists.txt create mode 100644 int32_publisher/main.c create mode 100644 int32_publisher/package.xml create mode 100644 int32_subscriber/CMakeLists.txt create mode 100644 int32_subscriber/main.c create mode 100644 int32_subscriber/package.xml create mode 100644 string_publisher/CMakeLists.txt create mode 100644 string_publisher/main.c create mode 100644 string_publisher/package.xml create mode 100644 string_subscriber/CMakeLists.txt create mode 100644 string_subscriber/main.c create mode 100644 string_subscriber/package.xml diff --git a/int32_publisher/CMakeLists.txt b/int32_publisher/CMakeLists.txt new file mode 100644 index 0000000..8364e05 --- /dev/null +++ b/int32_publisher/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(int32_publisher) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/int32_publisher/main.c b/int32_publisher/main.c new file mode 100644 index 0000000..ea05f86 --- /dev/null +++ b/int32_publisher/main.c @@ -0,0 +1,26 @@ +#include +#include + +#include + +int main(int argc, char *argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "publisher_example", 1); + + std_msgs__msg__Int32 msg; + msg.data = -1; + + while (rclc_ok()) + { + printf("Sending: '%i'\n", msg.data++); + rclc_publish(publisher, (const void*)&msg); + rclc_spin_node_once(node, 500); + } + rclc_destroy_publisher(publisher); + rclc_destroy_node(node); + return 0; +} \ No newline at end of file diff --git a/int32_publisher/package.xml b/int32_publisher/package.xml new file mode 100644 index 0000000..afb1f65 --- /dev/null +++ b/int32_publisher/package.xml @@ -0,0 +1,16 @@ + + + + int32_publisher + 0.0.1 + Example of a publisher using int32 + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/int32_subscriber/CMakeLists.txt b/int32_subscriber/CMakeLists.txt new file mode 100644 index 0000000..d0786ab --- /dev/null +++ b/int32_subscriber/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(int32_subscriber) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/int32_subscriber/main.c b/int32_subscriber/main.c new file mode 100644 index 0000000..9184596 --- /dev/null +++ b/int32_subscriber/main.c @@ -0,0 +1,26 @@ +#include +#include + +#include + +void on_message(const void* msgin) +{ + const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; + printf("I heard: [%i]\n", msg->data); +} + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), + "subscription_example", on_message, 1, false); + + rclc_spin_node(node); + + rclc_destroy_subscription(sub); + rclc_destroy_node(node); + return 0; +} diff --git a/int32_subscriber/package.xml b/int32_subscriber/package.xml new file mode 100644 index 0000000..8adb113 --- /dev/null +++ b/int32_subscriber/package.xml @@ -0,0 +1,16 @@ + + + + int32_subscriber + 0.0.1 + Example of a subscriber using int32 + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/string_publisher/CMakeLists.txt b/string_publisher/CMakeLists.txt new file mode 100644 index 0000000..1483573 --- /dev/null +++ b/string_publisher/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(string_publisher) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/string_publisher/main.c b/string_publisher/main.c new file mode 100644 index 0000000..26b5f38 --- /dev/null +++ b/string_publisher/main.c @@ -0,0 +1,35 @@ +#include +#include + +#include + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_publisher_t* publisher = + rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", 1); + + std_msgs__msg__String msg; + char buff[128] = {0}; + msg.data.data = buff; + msg.data.capacity = sizeof(buff); + msg.data.size = 0; + + int num = 0; + while (rclc_ok()) + { + msg.data.size = snprintf(msg.data.data, msg.data.capacity, "Hello World %i", num++); + if (msg.data.size > msg.data.capacity) + msg.data.size = 0; + + printf("Sending: '%s'\n", msg.data.data); + rclc_publish(publisher, (const void*)&msg); + rclc_spin_node_once(node, 500); + } + rclc_destroy_publisher(publisher); + rclc_destroy_node(node); + return 0; +} diff --git a/string_publisher/package.xml b/string_publisher/package.xml new file mode 100644 index 0000000..f1d76ac --- /dev/null +++ b/string_publisher/package.xml @@ -0,0 +1,16 @@ + + + + string_publisher + 0.0.1 + Example of a string publisher + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + diff --git a/string_subscriber/CMakeLists.txt b/string_subscriber/CMakeLists.txt new file mode 100644 index 0000000..6aa46f9 --- /dev/null +++ b/string_subscriber/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +project(string_subscriber) + +find_package(ament_cmake REQUIRED) +find_package(rclc QUIET) +find_package(std_msgs REQUIRED) + +# Do not compile package if rclcpp is not found +if (NOT rclc_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + return() +endif() + +add_executable(${PROJECT_NAME} main.c) +ament_target_dependencies(${PROJECT_NAME} rclc std_msgs) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/string_subscriber/main.c b/string_subscriber/main.c new file mode 100644 index 0000000..785f2a4 --- /dev/null +++ b/string_subscriber/main.c @@ -0,0 +1,26 @@ +#include +#include + +#include + +void on_message(const void* msgin) +{ + const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; + printf("I heard: [%s]\n", msg->data.data); +} + +int main(int argc, char* argv[]) +{ + (void)argc; + (void)argv; + rclc_init(0, NULL); + rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), + "std_msgs_msg_String", on_message, 1, false); + + rclc_spin_node(node); + + rclc_destroy_subscription(sub); + rclc_destroy_node(node); + return 0; +} diff --git a/string_subscriber/package.xml b/string_subscriber/package.xml new file mode 100644 index 0000000..24eab37 --- /dev/null +++ b/string_subscriber/package.xml @@ -0,0 +1,16 @@ + + + + string_subscriber + 0.0.1 + Example of a string subscriber + borjaouterelo + Apache License 2.0 + ament_cmake + rclc + std_msgs + + ament_cmake + + + From 4bef3c3c6cddfb144918808a612d5def3b0df68a Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Fri, 5 Oct 2018 07:33:38 +0200 Subject: [PATCH 14/27] fixed ament warning --- RAD0_actuator/CMakeLists.txt | 1 + RAD0_actuator/main.c | 5 +++++ RAD0_altitude_sensor/CMakeLists.txt | 1 + RAD0_altitude_sensor/main.c | 4 +++- RAD0_control/CMakeLists.txt | 1 + RAD0_display/CMakeLists.txt | 1 + RAD0_display/main.c | 6 +++++- complex_msg_publisher/CMakeLists.txt | 1 + complex_msg_publisher/main.c | 8 ++++++++ complex_msg_subscriber/CMakeLists.txt | 1 + complex_msg_subscriber/main.c | 4 ++++ int32_publisher/CMakeLists.txt | 1 + int32_publisher/main.c | 7 +++++-- int32_subscriber/CMakeLists.txt | 1 + int32_subscriber/main.c | 6 +++++- string_publisher/CMakeLists.txt | 1 + string_publisher/main.c | 4 ++++ string_subscriber/CMakeLists.txt | 1 + string_subscriber/main.c | 4 ++++ 19 files changed, 53 insertions(+), 5 deletions(-) diff --git a/RAD0_actuator/CMakeLists.txt b/RAD0_actuator/CMakeLists.txt index 3d023b8..66f589a 100644 --- a/RAD0_actuator/CMakeLists.txt +++ b/RAD0_actuator/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/RAD0_actuator/main.c b/RAD0_actuator/main.c index 96835bd..b73847d 100644 --- a/RAD0_actuator/main.c +++ b/RAD0_actuator/main.c @@ -5,6 +5,8 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; + static rclc_publisher_t* engine_pub; static uint32_t engine_power = 100; @@ -40,8 +42,11 @@ int main(int argc, char* argv[]) rclc_init(0, NULL); node = rclc_create_node("actuator", ""); + ASSERT(node); engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", engine_on_message, 1, false); + ASSERT(engine_sub); engine_pub = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", 1); + ASSERT(engine_pub); // Publish new altitude std_msgs__msg__UInt32 msg_out; diff --git a/RAD0_altitude_sensor/CMakeLists.txt b/RAD0_altitude_sensor/CMakeLists.txt index 1978528..1c6c2e2 100644 --- a/RAD0_altitude_sensor/CMakeLists.txt +++ b/RAD0_altitude_sensor/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/RAD0_altitude_sensor/main.c b/RAD0_altitude_sensor/main.c index 891f03b..8197a62 100644 --- a/RAD0_altitude_sensor/main.c +++ b/RAD0_altitude_sensor/main.c @@ -6,7 +6,7 @@ #include #include - +#define ASSERT(ptr) if (ptr == NULL) return -1; /** * @brief @@ -25,7 +25,9 @@ int main(int argc, char *argv[]) rclc_publisher_t* publisher = NULL; node = rclc_create_node("altitude_sensor", ""); + ASSERT(node); publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", 1); + ASSERT(publisher); double A = 0; diff --git a/RAD0_control/CMakeLists.txt b/RAD0_control/CMakeLists.txt index eb56335..9969c0a 100644 --- a/RAD0_control/CMakeLists.txt +++ b/RAD0_control/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() return() endif() diff --git a/RAD0_display/CMakeLists.txt b/RAD0_display/CMakeLists.txt index 8fadc51..7d0773e 100644 --- a/RAD0_display/CMakeLists.txt +++ b/RAD0_display/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/RAD0_display/main.c b/RAD0_display/main.c index 0d14c86..cdb4576 100644 --- a/RAD0_display/main.c +++ b/RAD0_display/main.c @@ -6,6 +6,7 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; static float altitude; static uint32_t engine_power; @@ -84,10 +85,13 @@ int main(int argc, char *argv[]) rclc_init(0, NULL); node = rclc_create_node("display", ""); - + ASSERT(node); alert_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_alert_message, 1, false); + ASSERT(alert_subscription); altitude_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", on_altitude_message, 1, false); + ASSERT(altitude_subscription); power_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt32), "std_msgs_msg_UInt32", on_power_message, 1, false); + ASSERT(power_subscription); rclc_spin_node(node); diff --git a/complex_msg_publisher/CMakeLists.txt b/complex_msg_publisher/CMakeLists.txt index 95bb495..2235b55 100644 --- a/complex_msg_publisher/CMakeLists.txt +++ b/complex_msg_publisher/CMakeLists.txt @@ -10,6 +10,7 @@ find_package(complex_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/complex_msg_publisher/main.c b/complex_msg_publisher/main.c index c0fefe1..3e31bdb 100644 --- a/complex_msg_publisher/main.c +++ b/complex_msg_publisher/main.c @@ -9,8 +9,16 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("publisher_node", ""); + if (node == NULL) + { + return -1; + } rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(complex_msgs, msg, NestedMsgTest), "complex_msgs_msg_NestedMsgTest", 1); + if (publisher == NULL) + { + return -1; + } complex_msgs__msg__NestedMsgTest msg; char Buff1[30]; diff --git a/complex_msg_subscriber/CMakeLists.txt b/complex_msg_subscriber/CMakeLists.txt index f4f846e..1bde415 100644 --- a/complex_msg_subscriber/CMakeLists.txt +++ b/complex_msg_subscriber/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(complex_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/complex_msg_subscriber/main.c b/complex_msg_subscriber/main.c index 4a6d6a5..def4b0b 100644 --- a/complex_msg_subscriber/main.c +++ b/complex_msg_subscriber/main.c @@ -3,6 +3,8 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; + void on_message(const void* msgin) { const complex_msgs__msg__NestedMsgTest* msg = (const complex_msgs__msg__NestedMsgTest*)msgin; @@ -34,7 +36,9 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("subscription_node", ""); + ASSERT(node); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(complex_msgs, msg, NestedMsgTest), "complex_msgs_msg_NestedMsgTest", on_message, 1, false); + ASSERT(sub); rclc_spin_node(node); diff --git a/int32_publisher/CMakeLists.txt b/int32_publisher/CMakeLists.txt index 8364e05..9b4659e 100644 --- a/int32_publisher/CMakeLists.txt +++ b/int32_publisher/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/int32_publisher/main.c b/int32_publisher/main.c index ea05f86..1dd7718 100644 --- a/int32_publisher/main.c +++ b/int32_publisher/main.c @@ -3,14 +3,17 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; + int main(int argc, char *argv[]) { (void)argc; (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("publisher_node", ""); - rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "publisher_example", 1); - + ASSERT(node); + rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", 1); + ASSERT(publisher); std_msgs__msg__Int32 msg; msg.data = -1; diff --git a/int32_subscriber/CMakeLists.txt b/int32_subscriber/CMakeLists.txt index d0786ab..76b321d 100644 --- a/int32_subscriber/CMakeLists.txt +++ b/int32_subscriber/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/int32_subscriber/main.c b/int32_subscriber/main.c index 9184596..62c1edc 100644 --- a/int32_subscriber/main.c +++ b/int32_subscriber/main.c @@ -3,6 +3,8 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; + void on_message(const void* msgin) { const std_msgs__msg__Int32* msg = (const std_msgs__msg__Int32*)msgin; @@ -15,8 +17,10 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("subscription_node", ""); + ASSERT(node); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), - "subscription_example", on_message, 1, false); + "std_msgs_msg_Int32", on_message, 1, false); + ASSERT(sub); rclc_spin_node(node); diff --git a/string_publisher/CMakeLists.txt b/string_publisher/CMakeLists.txt index 1483573..88fad03 100644 --- a/string_publisher/CMakeLists.txt +++ b/string_publisher/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/string_publisher/main.c b/string_publisher/main.c index 26b5f38..57d808e 100644 --- a/string_publisher/main.c +++ b/string_publisher/main.c @@ -3,14 +3,18 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; + int main(int argc, char* argv[]) { (void)argc; (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("publisher_node", ""); + ASSERT(node); rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", 1); + ASSERT(publisher); std_msgs__msg__String msg; char buff[128] = {0}; diff --git a/string_subscriber/CMakeLists.txt b/string_subscriber/CMakeLists.txt index 6aa46f9..99a3536 100644 --- a/string_subscriber/CMakeLists.txt +++ b/string_subscriber/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(std_msgs REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") + ament_package() return() endif() diff --git a/string_subscriber/main.c b/string_subscriber/main.c index 785f2a4..556b18d 100644 --- a/string_subscriber/main.c +++ b/string_subscriber/main.c @@ -3,6 +3,8 @@ #include +#define ASSERT(ptr) if (ptr == NULL) return -1; + void on_message(const void* msgin) { const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin; @@ -15,8 +17,10 @@ int main(int argc, char* argv[]) (void)argv; rclc_init(0, NULL); rclc_node_t* node = rclc_create_node("subscription_node", ""); + ASSERT(node); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_message, 1, false); + ASSERT(sub); rclc_spin_node(node); From 50f65ef3b91713334b0f62e390b3bc094ce815b1 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Fri, 5 Oct 2018 13:02:53 +0200 Subject: [PATCH 15/27] Changes applied according to de discussion --- RAD0_control/README.md | 5 ----- 1 file changed, 5 deletions(-) diff --git a/RAD0_control/README.md b/RAD0_control/README.md index a8cdda4..e69de29 100644 --- a/RAD0_control/README.md +++ b/RAD0_control/README.md @@ -1,5 +0,0 @@ -# Minimal publisher examples - -This package contains a few different strategies for creating short nodes which blast out messages. -The `talker_timer_lambda` and `talker_timer_member_function` recipes create subclasses of `rclcpp::Node` and set up an `rclcpp::timer` to periodically call functions which publish messages. -The `talker_without_subclass` recipe instead instantiates a `rclcpp::Node` object *without* subclassing it, which works, but is not compatible with composition, and thus is no longer the recommended style for ROS 2 coding. From e817ab2aa98b0088d83df24010ee40e45c1f5852 Mon Sep 17 00:00:00 2001 From: Borja Outerelo Date: Tue, 16 Oct 2018 11:45:54 +0200 Subject: [PATCH 16/27] Refs #3552. Fixed package dependencies. --- RAD0_actuator/CMakeLists.txt | 4 +--- RAD0_altitude_sensor/CMakeLists.txt | 4 +--- RAD0_control/CMakeLists.txt | 1 + RAD0_display/CMakeLists.txt | 2 -- complex_msg_publisher/CMakeLists.txt | 8 ++------ complex_msg_subscriber/CMakeLists.txt | 6 ++---- int32_publisher/CMakeLists.txt | 4 ++-- int32_subscriber/CMakeLists.txt | 2 +- 8 files changed, 10 insertions(+), 21 deletions(-) diff --git a/RAD0_actuator/CMakeLists.txt b/RAD0_actuator/CMakeLists.txt index 66f589a..d4e2d3d 100644 --- a/RAD0_actuator/CMakeLists.txt +++ b/RAD0_actuator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(rad0_actuator) find_package(ament_cmake REQUIRED) @@ -21,6 +21,4 @@ install(TARGETS DESTINATION lib/${PROJECT_NAME} ) -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - ament_package() diff --git a/RAD0_altitude_sensor/CMakeLists.txt b/RAD0_altitude_sensor/CMakeLists.txt index 1c6c2e2..56c646f 100644 --- a/RAD0_altitude_sensor/CMakeLists.txt +++ b/RAD0_altitude_sensor/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(rad0_altitude_sensor) find_package(ament_cmake REQUIRED) @@ -23,6 +23,4 @@ ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} ) -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - ament_package() diff --git a/RAD0_control/CMakeLists.txt b/RAD0_control/CMakeLists.txt index 9969c0a..0132cd2 100644 --- a/RAD0_control/CMakeLists.txt +++ b/RAD0_control/CMakeLists.txt @@ -1,4 +1,5 @@ cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(rad0_control) # Default to C++14 diff --git a/RAD0_display/CMakeLists.txt b/RAD0_display/CMakeLists.txt index 7d0773e..7e25b98 100644 --- a/RAD0_display/CMakeLists.txt +++ b/RAD0_display/CMakeLists.txt @@ -21,6 +21,4 @@ ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} ) -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - ament_package() diff --git a/complex_msg_publisher/CMakeLists.txt b/complex_msg_publisher/CMakeLists.txt index 2235b55..b506923 100644 --- a/complex_msg_publisher/CMakeLists.txt +++ b/complex_msg_publisher/CMakeLists.txt @@ -1,12 +1,11 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(complex_msg_publisher) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) find_package(complex_msgs REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") @@ -14,15 +13,12 @@ if (NOT rclc_FOUND) return() endif() - add_executable(${PROJECT_NAME} main.c) -ament_target_dependencies(${PROJECT_NAME} rclc complex_msgs) +ament_target_dependencies(${PROJECT_NAME} rclc complex_msgs) install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} ) -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - ament_package() diff --git a/complex_msg_subscriber/CMakeLists.txt b/complex_msg_subscriber/CMakeLists.txt index 1bde415..7347306 100644 --- a/complex_msg_subscriber/CMakeLists.txt +++ b/complex_msg_subscriber/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(complex_msg_subscriber) find_package(ament_cmake REQUIRED) @@ -14,13 +14,11 @@ if (NOT rclc_FOUND) endif() add_executable(${PROJECT_NAME} main.c) -ament_target_dependencies(${PROJECT_NAME} rclc complex_msgs) +ament_target_dependencies(${PROJECT_NAME} rclc complex_msgs) install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} ) -target_link_libraries(${PROJECT_NAME} micrortps_client microcdr) - ament_package() diff --git a/int32_publisher/CMakeLists.txt b/int32_publisher/CMakeLists.txt index 9b4659e..6fc1f7c 100644 --- a/int32_publisher/CMakeLists.txt +++ b/int32_publisher/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(int32_publisher) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) find_package(std_msgs REQUIRED) -# Do not compile package if rclcpp is not found +# Do not compile package if rclc is not found if (NOT rclc_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclc is not installed") ament_package() diff --git a/int32_subscriber/CMakeLists.txt b/int32_subscriber/CMakeLists.txt index 76b321d..de9d1f3 100644 --- a/int32_subscriber/CMakeLists.txt +++ b/int32_subscriber/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) project(int32_subscriber) find_package(ament_cmake REQUIRED) From 12d23f65ea782fbdf959073f62cb9cefead8ef76 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Wed, 10 Oct 2018 10:53:12 +0200 Subject: [PATCH 17/27] Refs #3476 - Create Readme.md for uros-demos. --- README.md | 360 ++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 360 insertions(+) diff --git a/README.md b/README.md index e69de29..1b2b405 100644 --- a/README.md +++ b/README.md @@ -0,0 +1,360 @@ +# Overview + +The main porpuse for this repo is to organize all packages for the [Micro-ROS Poject]() funcionalities demostrations. + + +# Package clusters + +The repository contains the belows packages clusters: + + +## Simple message demostration + +### Packages + +#### Int32_publisher + +The porpuse of the package is to publicate a one of the simplest ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. +For each publication, the message value will be increased in one unit order to see in the subcriber side the menssage variations. + + +#### Int32_subscriber + +The porpuse of the package is to subcribe to one of the simplest ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. + + +### Run demostration + +To run the demostration you have first to build all required packages in a Micro-ROS workspace. +To read farther about how to build the Micro-ROS workspace click [here](). + +```bash +cd ~/ros2_ws +colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to int32_publisher int32_subscriber uros_agent +``` + + +Configure enviroment + +```bash +. ~/ros2_ws/install/local_setup.bash +``` + + +Run the Micro-xrce agent + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 +``` + +You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 > /dev/null & +``` + + +Run the publisher. + +```bash + ~/ros2_ws/install/int32_publisher/lib/int32_publisher/./int32_publisher +``` + +You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. + +```bash + ~/ros2_ws/install/int32_publisher/lib/int32_publisher/./int32_publisher > /dev/null & +``` + +Run the subcriber. + +```bash +~/ros2_ws/install/int32_subscriber/lib/int32_subscriber/./int32_subscriber +``` + +## String message demostration + +### Packages + +#### string_publisher + +The porpuse of the package is to publicate a simple string ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. +For each publication, the message string number will be increased in one unit order to see in the subcriber side the menssage variations. + + +#### String_subscriber + +The porpuse of the package is to subcribe to a simple string ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. + + +### Run demostration + +To run the demostration you have first to build all required packages in a Micro-ROS workspace. +To read farther about how to build the Micro-ROS workspace click [here](). + +```bash +cd ~/ros2_ws +colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to string_publisher string_subscriber uros_agent +``` + +Configure enviroment + +```bash +. ~/ros2_ws/install/local_setup.bash +``` + + +Run the Micro-xrce agent + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 +``` + +You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 > /dev/null & +``` + + +Run the publisher. + +```bash + ~/ros2_ws/install/string_publisher/lib/string_publisher/./string_publisher +``` + +You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. + +```bash + ~/ros2_ws/install/string_publisher/lib/string_publisher/./string_publisher > /dev/null & +``` + +Run the subcriber. + +```bash +~/ros2_ws/install/string_subscriber/lib/string_subscriber/./string_subscriber +``` + + +## Complex message demostration + +### Packages + +#### complex_msg + +One of the porpuses of the package is to demostrate how typesupport code is generated for a complex message. +Also, the generation of a complex ROS2 structure message will be used to demostrate how down layers (rcl, typesupport and rmw) handle it. +The message structure content the following types: +- All primitive data types. +- Nesting menssage data. +- Unbonded string data. + + +#### Complex_msg_publisher + +The porpuse of the package is to publicate a complex ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. +For each publication, the message values will be increased in one unit order to see in the subcriber side the menssage variations. + + +#### Complex_msg_subscriber + +The porpuse of the package is to subcribe a complex ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. + + +### Run demostration + +To run the demostration you have first to build all required packages in a Micro-ROS workspace. +To read farther about how to build the Micro-ROS workspace click [here](). + +```bash +cd ~/ros2_ws +colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to complex_msgs complex_msg_publisher complex_msg_subscriber uros_agent +``` + +Configure enviroment + +```bash +. ~/ros2_ws/install/local_setup.bash +``` + + +Run the Micro-xrce agent + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 +``` + +You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 > /dev/null & +``` + + +Run the publisher. + +```bash + ~/ros2_ws/install/complex_msg_publisher/lib/complex_msg_publisher/./complex_msg_publisher +``` + +You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. + +```bash + ~/ros2_ws/install/complex_msg_publisher/lib/complex_msg_publisher/./complex_msg_publisher > /dev/null & +``` + +Run the subcriber. + +```bash +~/ros2_ws/install/complex_msg_subscriber/lib/complex_msg_subscriber/./complex_msg_subscriber +``` + + +## Real aplication demostration + +This purpuse of the packages is to demostrate Micro-Ros stack can be used in a real aplication scenario. +In this demostration an altitude control system will be simulated. +The main purpuse of this is to see how Micro-Ros comunicates with Ros2 nodes. + +For farther information about this demostration click [here]() + + +### Packages + +#### RAD0_actuator + +The mission of this node is to simulate a dummy altitude engine power actuator. +It will receive power increments and publicate the total power amount as a DDS topic. + +The node will be built using the Micro-Ros middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). + +It is meant to be running in on a microcontroller processor but for this demostration, the node will run on the host PC. +The node will be conected to the DDS world throw a micro-xrce-agent. + + +#### RAD0_altitude_sensor + +The mission of this node is to simulate a dummy altitude sensor. +It will publicate the altitude variations as a DDS topic. + +The node will be built using the Micro-Ros middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). + +It is meant to be running in on a microcontroller processor but for this demostration, the node will run on the host PC. +The node will be conected to the DDS world throw a micro-xrce-agent. + + +#### RAD0_control + +The mission of this node is to read altitude values and send to the actuator engine variations. +It also will publicate the status (OK, WARNING or FAILURE) as a DDS topic. +The status will depend on the altitude value. + +The node will be built using the ROS2 middleware packages (rmw_fastrtps and rosidl_typesupport_fastrtps). + +It is meant to be running in on a microcontroler processor and will be directly conected to de dds wold. + +#### RAD0_display + +The mission of this node is to simulate one LCD screen that will print the important parameters. +It will subcribe to the altitude, power and status messages availables as a DDS topic. + +The node will be built using the Micro-Ros middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). + +It is meant to be running in on a microcontroller processor but for this demostration, the node will run on the host PC. +The node will be conected to the DDS world throw a micro-xrce-agent. + + +### Run demostration + +Note: For this demostraton you need at least two open termninals, one for the Micro-ROS workspace and the other for the ROS2 workspace. + +#### Micro-ROS nodes + +To run the demostration you have first to build all required packages in a Micro-ROS workspace. +To read farther about how to build the Micro-ROS workspace click [here](). + + +```bash +cd ~/ros2_ws +colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to rad0_actuator rad0_display rad0_altitude_sensor uros_agent +``` + +Configure enviroment + +```bash +. ~/ros2_ws/install/local_setup.bash +``` + + +Run the Micro-xrce agent + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 +``` + +You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. + +```bash +cd ~/ros2_ws/install/micrortps_agent/bin +./MicroRTPSAgent udp 8888 > /dev/null & +``` + +Run the altitude_sensor node. + +```bash + ~/ros2_ws/install/rad0_altitude_sensor/lib/rad0_altitude_sensor/./rad0_altitude_sensor +``` + +You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. + +```bash + ~/ros2_ws/install/rad0_altitude_sensor/lib/rad0_altitude_sensor/./rad0_altitude_sensor > /dev/null & +``` + +Run the actitude node. + +```bash + ~/ros2_ws/install/rad0_actuator/lib/rad0_actuator/./rad0_actuator +``` + +You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. + +```bash + ~/ros2_ws/install/rad0_actuator/lib/rad0_actuator/./rad0_actuator > /dev/null & +``` + +Run the display node. + +```bash +~/ros2_ws/install/rad0_display/lib/rad0_display/./rad0_display +``` + +#### ROS2 nodes + +To run the demostration you have first to build all required packages in a ROS2 workspace. +To read farther about how to build the ROS2 workspace click [here](). + + +```bash +cd ~/ros2_ws +colcon build --packages-up-to rad0_control +``` + +Configure enviroment + +```bash +. ~/ros2_ws/install/local_setup.bash +``` + +Run the display node. + +```bash +ros2 run control control & +``` From 886c6fae0424f4bb5535dc138430ed49bcbec183 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Tue, 16 Oct 2018 07:33:07 +0200 Subject: [PATCH 18/27] Review needed. Links are missing until migration to external networks. --- README.md | 27 +++++++++++++++------------ 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/README.md b/README.md index 1b2b405..f648921 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,11 @@ -# Overview - -The main porpuse for this repo is to organize all packages for the [Micro-ROS Poject]() funcionalities demostrations. + +# Overview +The main porpuse for this repo is to organize all packages for the [Micro-ROS Poject]() functionalities demostrations. +All packages contained in this repo are a part of the Micro-ROS poject stack. +For more information about Micro-ROS project click [here](). + # Package clusters The repository contains the belows packages clusters: @@ -48,7 +51,7 @@ cd ~/ros2_ws/install/micrortps_agent/bin ./MicroRTPSAgent udp 8888 ``` -You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. ```bash cd ~/ros2_ws/install/micrortps_agent/bin @@ -62,7 +65,7 @@ Run the publisher. ~/ros2_ws/install/int32_publisher/lib/int32_publisher/./int32_publisher ``` -You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. ```bash ~/ros2_ws/install/int32_publisher/lib/int32_publisher/./int32_publisher > /dev/null & @@ -113,7 +116,7 @@ cd ~/ros2_ws/install/micrortps_agent/bin ./MicroRTPSAgent udp 8888 ``` -You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. ```bash cd ~/ros2_ws/install/micrortps_agent/bin @@ -127,7 +130,7 @@ Run the publisher. ~/ros2_ws/install/string_publisher/lib/string_publisher/./string_publisher ``` -You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. ```bash ~/ros2_ws/install/string_publisher/lib/string_publisher/./string_publisher > /dev/null & @@ -189,7 +192,7 @@ cd ~/ros2_ws/install/micrortps_agent/bin ./MicroRTPSAgent udp 8888 ``` -You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. ```bash cd ~/ros2_ws/install/micrortps_agent/bin @@ -203,7 +206,7 @@ Run the publisher. ~/ros2_ws/install/complex_msg_publisher/lib/complex_msg_publisher/./complex_msg_publisher ``` -You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. ```bash ~/ros2_ws/install/complex_msg_publisher/lib/complex_msg_publisher/./complex_msg_publisher > /dev/null & @@ -299,7 +302,7 @@ cd ~/ros2_ws/install/micrortps_agent/bin ./MicroRTPSAgent udp 8888 ``` -You may prefert to run the Agent in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. ```bash cd ~/ros2_ws/install/micrortps_agent/bin @@ -312,7 +315,7 @@ Run the altitude_sensor node. ~/ros2_ws/install/rad0_altitude_sensor/lib/rad0_altitude_sensor/./rad0_altitude_sensor ``` -You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. ```bash ~/ros2_ws/install/rad0_altitude_sensor/lib/rad0_altitude_sensor/./rad0_altitude_sensor > /dev/null & @@ -324,7 +327,7 @@ Run the actitude node. ~/ros2_ws/install/rad0_actuator/lib/rad0_actuator/./rad0_actuator ``` -You may prefert to run the publisher in background and discatr all output in order still using the terminal for the next step. +You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. ```bash ~/ros2_ws/install/rad0_actuator/lib/rad0_actuator/./rad0_actuator > /dev/null & From 7143a7bd58fdedbd5deb5a378c62f13aca91b4e0 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Tue, 16 Oct 2018 14:01:40 +0200 Subject: [PATCH 19/27] logo size ajusted. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index f648921..010f2b0 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ - + # Overview From 40f046fc66a4046520152f19bc3c904dce160baa Mon Sep 17 00:00:00 2001 From: Borja Outerelo Date: Fri, 19 Oct 2018 11:07:38 +0200 Subject: [PATCH 20/27] Refs #3476. Cleans wording and spelling checks. --- README.md | 58 +++++++++++++++++++++++++++---------------------------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/README.md b/README.md index 010f2b0..a8973c1 100644 --- a/README.md +++ b/README.md @@ -1,32 +1,32 @@ - +# Micro ROS Demo -# Overview +## Overview The main porpuse for this repo is to organize all packages for the [Micro-ROS Poject]() functionalities demostrations. All packages contained in this repo are a part of the Micro-ROS poject stack. For more information about Micro-ROS project click [here](). -# Package clusters +## Package clusters The repository contains the belows packages clusters: -## Simple message demostration +### Simple message demostration -### Packages +#### Packages -#### Int32_publisher +##### Int32_publisher The porpuse of the package is to publicate a one of the simplest ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. For each publication, the message value will be increased in one unit order to see in the subcriber side the menssage variations. -#### Int32_subscriber +##### Int32_subscriber The porpuse of the package is to subcribe to one of the simplest ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. -### Run demostration +#### Run demostration To run the demostration you have first to build all required packages in a Micro-ROS workspace. To read farther about how to build the Micro-ROS workspace click [here](). @@ -48,7 +48,7 @@ Run the Micro-xrce agent ```bash cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 +./MicroXRCEDDSAgent udp 8888 ``` You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. @@ -77,22 +77,22 @@ Run the subcriber. ~/ros2_ws/install/int32_subscriber/lib/int32_subscriber/./int32_subscriber ``` -## String message demostration +### String message demostration -### Packages +#### Packages -#### string_publisher +##### string_publisher The porpuse of the package is to publicate a simple string ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. For each publication, the message string number will be increased in one unit order to see in the subcriber side the menssage variations. -#### String_subscriber +##### String_subscriber The porpuse of the package is to subcribe to a simple string ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. -### Run demostration +#### Run demostration To run the demostration you have first to build all required packages in a Micro-ROS workspace. To read farther about how to build the Micro-ROS workspace click [here](). @@ -143,11 +143,11 @@ Run the subcriber. ``` -## Complex message demostration +### Complex message demostration -### Packages +#### Packages -#### complex_msg +##### complex_msg One of the porpuses of the package is to demostrate how typesupport code is generated for a complex message. Also, the generation of a complex ROS2 structure message will be used to demostrate how down layers (rcl, typesupport and rmw) handle it. @@ -157,18 +157,18 @@ The message structure content the following types: - Unbonded string data. -#### Complex_msg_publisher +##### Complex_msg_publisher The porpuse of the package is to publicate a complex ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. For each publication, the message values will be increased in one unit order to see in the subcriber side the menssage variations. -#### Complex_msg_subscriber +##### Complex_msg_subscriber The porpuse of the package is to subcribe a complex ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. -### Run demostration +#### Run demostration To run the demostration you have first to build all required packages in a Micro-ROS workspace. To read farther about how to build the Micro-ROS workspace click [here](). @@ -219,7 +219,7 @@ Run the subcriber. ``` -## Real aplication demostration +### Real aplication demostration This purpuse of the packages is to demostrate Micro-Ros stack can be used in a real aplication scenario. In this demostration an altitude control system will be simulated. @@ -228,9 +228,9 @@ The main purpuse of this is to see how Micro-Ros comunicates with Ros2 nodes. For farther information about this demostration click [here]() -### Packages +#### Packages -#### RAD0_actuator +##### RAD0_actuator The mission of this node is to simulate a dummy altitude engine power actuator. It will receive power increments and publicate the total power amount as a DDS topic. @@ -241,7 +241,7 @@ It is meant to be running in on a microcontroller processor but for this demostr The node will be conected to the DDS world throw a micro-xrce-agent. -#### RAD0_altitude_sensor +##### RAD0_altitude_sensor The mission of this node is to simulate a dummy altitude sensor. It will publicate the altitude variations as a DDS topic. @@ -252,7 +252,7 @@ It is meant to be running in on a microcontroller processor but for this demostr The node will be conected to the DDS world throw a micro-xrce-agent. -#### RAD0_control +##### RAD0_control The mission of this node is to read altitude values and send to the actuator engine variations. It also will publicate the status (OK, WARNING or FAILURE) as a DDS topic. @@ -262,7 +262,7 @@ The node will be built using the ROS2 middleware packages (rmw_fastrtps and rosi It is meant to be running in on a microcontroler processor and will be directly conected to de dds wold. -#### RAD0_display +##### RAD0_display The mission of this node is to simulate one LCD screen that will print the important parameters. It will subcribe to the altitude, power and status messages availables as a DDS topic. @@ -273,11 +273,11 @@ It is meant to be running in on a microcontroller processor but for this demostr The node will be conected to the DDS world throw a micro-xrce-agent. -### Run demostration +#### Run demostration Note: For this demostraton you need at least two open termninals, one for the Micro-ROS workspace and the other for the ROS2 workspace. -#### Micro-ROS nodes +##### Micro-ROS nodes To run the demostration you have first to build all required packages in a Micro-ROS workspace. To read farther about how to build the Micro-ROS workspace click [here](). @@ -339,7 +339,7 @@ Run the display node. ~/ros2_ws/install/rad0_display/lib/rad0_display/./rad0_display ``` -#### ROS2 nodes +##### ROS2 nodes To run the demostration you have first to build all required packages in a ROS2 workspace. To read farther about how to build the ROS2 workspace click [here](). From 319c0b2488fe4cd96ceab4ce4e6fed6f102d68f4 Mon Sep 17 00:00:00 2001 From: Borja Outerelo Date: Wed, 31 Oct 2018 15:52:27 +0100 Subject: [PATCH 21/27] Improvements on README file --- README.md | 223 ++++++++++++++++++++++++------------------------------ 1 file changed, 100 insertions(+), 123 deletions(-) diff --git a/README.md b/README.md index a8973c1..1ca914f 100644 --- a/README.md +++ b/README.md @@ -2,311 +2,289 @@ ## Overview -The main porpuse for this repo is to organize all packages for the [Micro-ROS Poject]() functionalities demostrations. -All packages contained in this repo are a part of the Micro-ROS poject stack. -For more information about Micro-ROS project click [here](). - -## Package clusters +The primary purpose for this repository is to organise all packages for the [Micro-ROS project](https://microros.github.io/micro-ROS/) functionalities demonstrations. +All packages contained in this repository are a part of the Micro-ROS project stack. +For more information about Micro-ROS project click [here](https://microros.github.io/micro-ROS/). -The repository contains the belows packages clusters: +## Package clusters +The repository contains the below packages clusters: -### Simple message demostration +### Simple message demonstration #### Packages ##### Int32_publisher -The porpuse of the package is to publicate a one of the simplest ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. -For each publication, the message value will be increased in one unit order to see in the subcriber side the menssage variations. - +The purpose of the package is to publish one of the most basic ROS 2 messages and demonstrate how Micro-ROS layers (rcl, typesupport and rmw) handle it. +For each publication, the message value increases in one unit order to see in the subscriber side the message variations. ##### Int32_subscriber -The porpuse of the package is to subcribe to one of the simplest ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. - +The purpose of the package is to subscribe to one of the most basic ROS 2 messages and demonstrate how Micro-ROS layers (rcl, typesupport and rmw) handle it. -#### Run demostration +#### Run demonstration -To run the demostration you have first to build all required packages in a Micro-ROS workspace. -To read farther about how to build the Micro-ROS workspace click [here](). +To run the demonstration, as a first step, you have to build all the required packages in a Micro-ROS workspace. +To read further about how to build the Micro-ROS workspace click [here](). ```bash cd ~/ros2_ws colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to int32_publisher int32_subscriber uros_agent ``` - -Configure enviroment +Configure the environment ```bash . ~/ros2_ws/install/local_setup.bash ``` - -Run the Micro-xrce agent +Run the Micro XRCE-DDS Agent ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroXRCEDDSAgent udp 8888 +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 ``` -You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the Agent in the background and discard all outputs to keep using the same terminal for the next step. ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 > /dev/null & +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 > /dev/null & ``` - Run the publisher. ```bash ~/ros2_ws/install/int32_publisher/lib/int32_publisher/./int32_publisher ``` -You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the publisher in the background and discard all outputs to keep using the terminal for the next step. ```bash ~/ros2_ws/install/int32_publisher/lib/int32_publisher/./int32_publisher > /dev/null & ``` -Run the subcriber. +Run the subscriber. ```bash ~/ros2_ws/install/int32_subscriber/lib/int32_subscriber/./int32_subscriber ``` -### String message demostration +### String message demonstration #### Packages ##### string_publisher -The porpuse of the package is to publicate a simple string ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. -For each publication, the message string number will be increased in one unit order to see in the subcriber side the menssage variations. - +The purpose of the package is to publish a simple string ROS 2 message and demonstrate how Micro-ROS layers (rcl, typesupport and rmw) handle it. +For each publication, the message string number increases in one unit order to see in the subscriber side the message variations. ##### String_subscriber -The porpuse of the package is to subcribe to a simple string ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. - +The purpose of the package is to subscribe to a simple string ROS 2 message and demonstrate how Micro-ROS layers (rcl, typesupport and rmw) handle it. -#### Run demostration +#### Run demonstration -To run the demostration you have first to build all required packages in a Micro-ROS workspace. -To read farther about how to build the Micro-ROS workspace click [here](). +To run the demonstration, as a first step, you have to build all the required packages in a Micro-ROS workspace. +To read further about how to build the Micro-ROS workspace click [here](). ```bash cd ~/ros2_ws colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to string_publisher string_subscriber uros_agent ``` -Configure enviroment +Configure the environment ```bash . ~/ros2_ws/install/local_setup.bash ``` - -Run the Micro-xrce agent +Run the Micro XRCE-DDS Agent ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 ``` -You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the Agent in the background and discard all outputs to keep using the same terminal for the next step. ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 > /dev/null & +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 > /dev/null & ``` - Run the publisher. ```bash ~/ros2_ws/install/string_publisher/lib/string_publisher/./string_publisher ``` -You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the publisher in the background and discard all outputs in order still using the terminal for the next step. ```bash ~/ros2_ws/install/string_publisher/lib/string_publisher/./string_publisher > /dev/null & ``` -Run the subcriber. +Run the subscriber. ```bash ~/ros2_ws/install/string_subscriber/lib/string_subscriber/./string_subscriber ``` - -### Complex message demostration +### Complex message demonstration #### Packages ##### complex_msg -One of the porpuses of the package is to demostrate how typesupport code is generated for a complex message. -Also, the generation of a complex ROS2 structure message will be used to demostrate how down layers (rcl, typesupport and rmw) handle it. -The message structure content the following types: +One of the purposes of the package is to demonstrate how typesupport code is generated for a complex message. +Also, the generation of a complex ROS 2 structure message is used to demonstrate how the different layers (rcl, typesupport and rmw) handle it. +The message structure contains the following types: + - All primitive data types. -- Nesting menssage data. +- Nested message data. - Unbonded string data. - ##### Complex_msg_publisher -The porpuse of the package is to publicate a complex ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. -For each publication, the message values will be increased in one unit order to see in the subcriber side the menssage variations. - +The purpose of the package is to publish a complex ROS 2 message and demonstrate how Micro-ROS layers (rcl, typesupport and rmw) handle it. +For each publication, the message values increases in one unit order to see in the subscriber side the message variations. ##### Complex_msg_subscriber -The porpuse of the package is to subcribe a complex ROS2 message and demostrate how Micro-ROS down layers (rcl, typesupport and rmw) handle it. +The purpose of the package is to subscribe to a complex ROS 2 message and demonstrate how Micro-ROS layers (rcl, typesupport and rmw) handle it. +#### Run demonstration -#### Run demostration - -To run the demostration you have first to build all required packages in a Micro-ROS workspace. -To read farther about how to build the Micro-ROS workspace click [here](). +To run the demonstration, as a first step, you have to build all the required packages in a Micro-ROS workspace. +To read further about how to build the Micro-ROS workspace click [here](). ```bash cd ~/ros2_ws colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to complex_msgs complex_msg_publisher complex_msg_subscriber uros_agent ``` -Configure enviroment +Configure the environment ```bash . ~/ros2_ws/install/local_setup.bash ``` - -Run the Micro-xrce agent +Run the Micro XRCE-DDS Agent ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 ``` -You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the Agent in the background and discard all outputs to keep using the same terminal for the next step. ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 > /dev/null & +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 > /dev/null & ``` - Run the publisher. ```bash ~/ros2_ws/install/complex_msg_publisher/lib/complex_msg_publisher/./complex_msg_publisher ``` -You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the Agent in the background and discard all outputs to keep using the same terminal for the next step. ```bash ~/ros2_ws/install/complex_msg_publisher/lib/complex_msg_publisher/./complex_msg_publisher > /dev/null & ``` -Run the subcriber. +Run the subscriber. ```bash ~/ros2_ws/install/complex_msg_subscriber/lib/complex_msg_subscriber/./complex_msg_subscriber ``` +### Real application demonstration -### Real aplication demostration - -This purpuse of the packages is to demostrate Micro-Ros stack can be used in a real aplication scenario. -In this demostration an altitude control system will be simulated. -The main purpuse of this is to see how Micro-Ros comunicates with Ros2 nodes. - -For farther information about this demostration click [here]() +This purpose of the packages is to demonstrate Micro-ROS stack can be used in a real application scenario. +In this demonstration, an altitude control system is simulated. +The primary purpose of this is to see how Micro-ROS communicates with ROS 2 nodes. +For further information about this demonstration click [here]() #### Packages ##### RAD0_actuator -The mission of this node is to simulate a dummy altitude engine power actuator. -It will receive power increments and publicate the total power amount as a DDS topic. +The mission of this node is to simulate a dummy engine power actuator. +It receives power increments and publishes the total power amount as a DDS topic. -The node will be built using the Micro-Ros middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). - -It is meant to be running in on a microcontroller processor but for this demostration, the node will run on the host PC. -The node will be conected to the DDS world throw a micro-xrce-agent. +The node is built using the Micro-ROS middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). +It is meant to be running in a microcontroller processor, but for this demonstration, the node runs on the host PC. +The node is connected to the DDS world through a Micro XRCE-DDS Agent. ##### RAD0_altitude_sensor -The mission of this node is to simulate a dummy altitude sensor. -It will publicate the altitude variations as a DDS topic. - -The node will be built using the Micro-Ros middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). +The mission of this node is to simulate a dummy altitude sensor. +It publishes the altitude variations as a DDS topic. -It is meant to be running in on a microcontroller processor but for this demostration, the node will run on the host PC. -The node will be conected to the DDS world throw a micro-xrce-agent. +The node is built using the Micro-ROS middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). +It is meant to be running in a microcontroller processor, but for this demonstration, the node runs on the host PC. +The node is connected to the DDS world through a Micro XRCE-DDS Agent. ##### RAD0_control The mission of this node is to read altitude values and send to the actuator engine variations. -It also will publicate the status (OK, WARNING or FAILURE) as a DDS topic. -The status will depend on the altitude value. +It also publishes the status (OK, WARNING or FAILURE) as a DDS topic. +The status depends on the altitude value. -The node will be built using the ROS2 middleware packages (rmw_fastrtps and rosidl_typesupport_fastrtps). +The node is built using the ROS 2 middleware packages (rmw_fastrtps and rosidl_typesupport_fastrtps). -It is meant to be running in on a microcontroler processor and will be directly conected to de dds wold. +It is meant to be running in on a regular PC, and it is directly connected to de DDS world. ##### RAD0_display -The mission of this node is to simulate one LCD screen that will print the important parameters. -It will subcribe to the altitude, power and status messages availables as a DDS topic. - -The node will be built using the Micro-Ros middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). +The mission of this node is to simulate one LCD screen that prints the critical parameters. +It subscribes to the altitude, power and status messages available as a DDS topic. -It is meant to be running in on a microcontroller processor but for this demostration, the node will run on the host PC. -The node will be conected to the DDS world throw a micro-xrce-agent. +The node is built using the Micro-ROS middleware packages (rmw_micro_xrcedds and rosidl_typesupport_microxrcedds). +It is meant to be running in a microcontroller processor, but for this demonstration, the node runs on the host PC. +The node is connected to the DDS world through a Micro XRCE-DDS Agent. -#### Run demostration +#### Run demonstration -Note: For this demostraton you need at least two open termninals, one for the Micro-ROS workspace and the other for the ROS2 workspace. +Note: For this demonstration, you need at least two open terminals, one for the Micro-ROS workspace and the other for the ROS 2 workspace. ##### Micro-ROS nodes -To run the demostration you have first to build all required packages in a Micro-ROS workspace. -To read farther about how to build the Micro-ROS workspace click [here](). - +To run the demonstration, as a first step, you have to build all the required packages in a Micro-ROS workspace. +To read further about how to build the Micro-ROS workspace click [here](). ```bash cd ~/ros2_ws colcon build --cmake-args -DBUILD_SHARED_LIBS=ON --packages-up-to rad0_actuator rad0_display rad0_altitude_sensor uros_agent ``` -Configure enviroment +Configure the environment ```bash . ~/ros2_ws/install/local_setup.bash ``` - -Run the Micro-xrce agent +Run the Micro XRCE-DDS Agent ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 ``` -You may prefer to run the Agent in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the Agent in the background and discard all outputs to keep using the same terminal for the next steps. ```bash -cd ~/ros2_ws/install/micrortps_agent/bin -./MicroRTPSAgent udp 8888 > /dev/null & +cd ~/ros2_ws/install/microxrcedds_agent/bin +./MicroXRCEAgent udp 8888 > /dev/null & ``` Run the altitude_sensor node. @@ -315,19 +293,19 @@ Run the altitude_sensor node. ~/ros2_ws/install/rad0_altitude_sensor/lib/rad0_altitude_sensor/./rad0_altitude_sensor ``` -You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the publisher in the background and discard all outputs to keep using the terminal for the next steps. ```bash ~/ros2_ws/install/rad0_altitude_sensor/lib/rad0_altitude_sensor/./rad0_altitude_sensor > /dev/null & ``` -Run the actitude node. +Run the actuator node. ```bash ~/ros2_ws/install/rad0_actuator/lib/rad0_actuator/./rad0_actuator ``` -You may prefer to run the publisher in background and discard all outputs in order still using the terminal for the next step. +You may prefer to run the publisher in the background and discard all outputs to keep using the terminal for the next steps. ```bash ~/ros2_ws/install/rad0_actuator/lib/rad0_actuator/./rad0_actuator > /dev/null & @@ -339,18 +317,17 @@ Run the display node. ~/ros2_ws/install/rad0_display/lib/rad0_display/./rad0_display ``` -##### ROS2 nodes - -To run the demostration you have first to build all required packages in a ROS2 workspace. -To read farther about how to build the ROS2 workspace click [here](). +##### ROS 2 nodes +To run the demonstration, you have first to build all required packages in a ROS 2 workspace. +To read further about how to build the ROS 2 workspace click [here](). ```bash cd ~/ros2_ws colcon build --packages-up-to rad0_control ``` -Configure enviroment +Configure the environment ```bash . ~/ros2_ws/install/local_setup.bash From 34afe5b03aa501c971fb8010f22a6e8d2f9abbce Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Thu, 25 Oct 2018 09:18:22 +0200 Subject: [PATCH 22/27] Refs #3637 - Translate demo to rclcpp. New folder structure. --- {RAD0_actuator => C/RAD0_actuator}/CMakeLists.txt | 0 {RAD0_actuator => C/RAD0_actuator}/main.c | 0 {RAD0_actuator => C/RAD0_actuator}/package.xml | 0 {RAD0_altitude_sensor => C/RAD0_altitude_sensor}/CMakeLists.txt | 0 {RAD0_altitude_sensor => C/RAD0_altitude_sensor}/main.c | 0 {RAD0_altitude_sensor => C/RAD0_altitude_sensor}/package.xml | 0 {RAD0_display => C/RAD0_display}/CMakeLists.txt | 0 {RAD0_display => C/RAD0_display}/main.c | 0 {RAD0_display => C/RAD0_display}/package.xml | 0 {complex_msg => C/complex_msg}/CMakeLists.txt | 0 {complex_msg => C/complex_msg}/msg/MultiStringTest.msg | 0 {complex_msg => C/complex_msg}/msg/NestedMsgTest.msg | 0 {complex_msg => C/complex_msg}/package.xml | 0 {complex_msg_publisher => C/complex_msg_publisher}/CMakeLists.txt | 0 {complex_msg_publisher => C/complex_msg_publisher}/main.c | 0 {complex_msg_publisher => C/complex_msg_publisher}/package.xml | 0 .../complex_msg_subscriber}/CMakeLists.txt | 0 {complex_msg_subscriber => C/complex_msg_subscriber}/main.c | 0 {complex_msg_subscriber => C/complex_msg_subscriber}/package.xml | 0 {int32_publisher => C/int32_publisher}/CMakeLists.txt | 0 {int32_publisher => C/int32_publisher}/main.c | 0 {int32_publisher => C/int32_publisher}/package.xml | 0 {int32_subscriber => C/int32_subscriber}/CMakeLists.txt | 0 {int32_subscriber => C/int32_subscriber}/main.c | 0 {int32_subscriber => C/int32_subscriber}/package.xml | 0 {string_publisher => C/string_publisher}/CMakeLists.txt | 0 {string_publisher => C/string_publisher}/main.c | 0 {string_publisher => C/string_publisher}/package.xml | 0 {string_subscriber => C/string_subscriber}/CMakeLists.txt | 0 {string_subscriber => C/string_subscriber}/main.c | 0 {string_subscriber => C/string_subscriber}/package.xml | 0 {RAD0_control => Cpp/RAD0_control}/CMakeLists.txt | 0 {RAD0_control => Cpp/RAD0_control}/README.md | 0 {RAD0_control => Cpp/RAD0_control}/main.cpp | 0 {RAD0_control => Cpp/RAD0_control}/package.xml | 0 35 files changed, 0 insertions(+), 0 deletions(-) rename {RAD0_actuator => C/RAD0_actuator}/CMakeLists.txt (100%) rename {RAD0_actuator => C/RAD0_actuator}/main.c (100%) rename {RAD0_actuator => C/RAD0_actuator}/package.xml (100%) rename {RAD0_altitude_sensor => C/RAD0_altitude_sensor}/CMakeLists.txt (100%) rename {RAD0_altitude_sensor => C/RAD0_altitude_sensor}/main.c (100%) rename {RAD0_altitude_sensor => C/RAD0_altitude_sensor}/package.xml (100%) rename {RAD0_display => C/RAD0_display}/CMakeLists.txt (100%) rename {RAD0_display => C/RAD0_display}/main.c (100%) rename {RAD0_display => C/RAD0_display}/package.xml (100%) rename {complex_msg => C/complex_msg}/CMakeLists.txt (100%) rename {complex_msg => C/complex_msg}/msg/MultiStringTest.msg (100%) rename {complex_msg => C/complex_msg}/msg/NestedMsgTest.msg (100%) rename {complex_msg => C/complex_msg}/package.xml (100%) rename {complex_msg_publisher => C/complex_msg_publisher}/CMakeLists.txt (100%) rename {complex_msg_publisher => C/complex_msg_publisher}/main.c (100%) rename {complex_msg_publisher => C/complex_msg_publisher}/package.xml (100%) rename {complex_msg_subscriber => C/complex_msg_subscriber}/CMakeLists.txt (100%) rename {complex_msg_subscriber => C/complex_msg_subscriber}/main.c (100%) rename {complex_msg_subscriber => C/complex_msg_subscriber}/package.xml (100%) rename {int32_publisher => C/int32_publisher}/CMakeLists.txt (100%) rename {int32_publisher => C/int32_publisher}/main.c (100%) rename {int32_publisher => C/int32_publisher}/package.xml (100%) rename {int32_subscriber => C/int32_subscriber}/CMakeLists.txt (100%) rename {int32_subscriber => C/int32_subscriber}/main.c (100%) rename {int32_subscriber => C/int32_subscriber}/package.xml (100%) rename {string_publisher => C/string_publisher}/CMakeLists.txt (100%) rename {string_publisher => C/string_publisher}/main.c (100%) rename {string_publisher => C/string_publisher}/package.xml (100%) rename {string_subscriber => C/string_subscriber}/CMakeLists.txt (100%) rename {string_subscriber => C/string_subscriber}/main.c (100%) rename {string_subscriber => C/string_subscriber}/package.xml (100%) rename {RAD0_control => Cpp/RAD0_control}/CMakeLists.txt (100%) rename {RAD0_control => Cpp/RAD0_control}/README.md (100%) rename {RAD0_control => Cpp/RAD0_control}/main.cpp (100%) rename {RAD0_control => Cpp/RAD0_control}/package.xml (100%) diff --git a/RAD0_actuator/CMakeLists.txt b/C/RAD0_actuator/CMakeLists.txt similarity index 100% rename from RAD0_actuator/CMakeLists.txt rename to C/RAD0_actuator/CMakeLists.txt diff --git a/RAD0_actuator/main.c b/C/RAD0_actuator/main.c similarity index 100% rename from RAD0_actuator/main.c rename to C/RAD0_actuator/main.c diff --git a/RAD0_actuator/package.xml b/C/RAD0_actuator/package.xml similarity index 100% rename from RAD0_actuator/package.xml rename to C/RAD0_actuator/package.xml diff --git a/RAD0_altitude_sensor/CMakeLists.txt b/C/RAD0_altitude_sensor/CMakeLists.txt similarity index 100% rename from RAD0_altitude_sensor/CMakeLists.txt rename to C/RAD0_altitude_sensor/CMakeLists.txt diff --git a/RAD0_altitude_sensor/main.c b/C/RAD0_altitude_sensor/main.c similarity index 100% rename from RAD0_altitude_sensor/main.c rename to C/RAD0_altitude_sensor/main.c diff --git a/RAD0_altitude_sensor/package.xml b/C/RAD0_altitude_sensor/package.xml similarity index 100% rename from RAD0_altitude_sensor/package.xml rename to C/RAD0_altitude_sensor/package.xml diff --git a/RAD0_display/CMakeLists.txt b/C/RAD0_display/CMakeLists.txt similarity index 100% rename from RAD0_display/CMakeLists.txt rename to C/RAD0_display/CMakeLists.txt diff --git a/RAD0_display/main.c b/C/RAD0_display/main.c similarity index 100% rename from RAD0_display/main.c rename to C/RAD0_display/main.c diff --git a/RAD0_display/package.xml b/C/RAD0_display/package.xml similarity index 100% rename from RAD0_display/package.xml rename to C/RAD0_display/package.xml diff --git a/complex_msg/CMakeLists.txt b/C/complex_msg/CMakeLists.txt similarity index 100% rename from complex_msg/CMakeLists.txt rename to C/complex_msg/CMakeLists.txt diff --git a/complex_msg/msg/MultiStringTest.msg b/C/complex_msg/msg/MultiStringTest.msg similarity index 100% rename from complex_msg/msg/MultiStringTest.msg rename to C/complex_msg/msg/MultiStringTest.msg diff --git a/complex_msg/msg/NestedMsgTest.msg b/C/complex_msg/msg/NestedMsgTest.msg similarity index 100% rename from complex_msg/msg/NestedMsgTest.msg rename to C/complex_msg/msg/NestedMsgTest.msg diff --git a/complex_msg/package.xml b/C/complex_msg/package.xml similarity index 100% rename from complex_msg/package.xml rename to C/complex_msg/package.xml diff --git a/complex_msg_publisher/CMakeLists.txt b/C/complex_msg_publisher/CMakeLists.txt similarity index 100% rename from complex_msg_publisher/CMakeLists.txt rename to C/complex_msg_publisher/CMakeLists.txt diff --git a/complex_msg_publisher/main.c b/C/complex_msg_publisher/main.c similarity index 100% rename from complex_msg_publisher/main.c rename to C/complex_msg_publisher/main.c diff --git a/complex_msg_publisher/package.xml b/C/complex_msg_publisher/package.xml similarity index 100% rename from complex_msg_publisher/package.xml rename to C/complex_msg_publisher/package.xml diff --git a/complex_msg_subscriber/CMakeLists.txt b/C/complex_msg_subscriber/CMakeLists.txt similarity index 100% rename from complex_msg_subscriber/CMakeLists.txt rename to C/complex_msg_subscriber/CMakeLists.txt diff --git a/complex_msg_subscriber/main.c b/C/complex_msg_subscriber/main.c similarity index 100% rename from complex_msg_subscriber/main.c rename to C/complex_msg_subscriber/main.c diff --git a/complex_msg_subscriber/package.xml b/C/complex_msg_subscriber/package.xml similarity index 100% rename from complex_msg_subscriber/package.xml rename to C/complex_msg_subscriber/package.xml diff --git a/int32_publisher/CMakeLists.txt b/C/int32_publisher/CMakeLists.txt similarity index 100% rename from int32_publisher/CMakeLists.txt rename to C/int32_publisher/CMakeLists.txt diff --git a/int32_publisher/main.c b/C/int32_publisher/main.c similarity index 100% rename from int32_publisher/main.c rename to C/int32_publisher/main.c diff --git a/int32_publisher/package.xml b/C/int32_publisher/package.xml similarity index 100% rename from int32_publisher/package.xml rename to C/int32_publisher/package.xml diff --git a/int32_subscriber/CMakeLists.txt b/C/int32_subscriber/CMakeLists.txt similarity index 100% rename from int32_subscriber/CMakeLists.txt rename to C/int32_subscriber/CMakeLists.txt diff --git a/int32_subscriber/main.c b/C/int32_subscriber/main.c similarity index 100% rename from int32_subscriber/main.c rename to C/int32_subscriber/main.c diff --git a/int32_subscriber/package.xml b/C/int32_subscriber/package.xml similarity index 100% rename from int32_subscriber/package.xml rename to C/int32_subscriber/package.xml diff --git a/string_publisher/CMakeLists.txt b/C/string_publisher/CMakeLists.txt similarity index 100% rename from string_publisher/CMakeLists.txt rename to C/string_publisher/CMakeLists.txt diff --git a/string_publisher/main.c b/C/string_publisher/main.c similarity index 100% rename from string_publisher/main.c rename to C/string_publisher/main.c diff --git a/string_publisher/package.xml b/C/string_publisher/package.xml similarity index 100% rename from string_publisher/package.xml rename to C/string_publisher/package.xml diff --git a/string_subscriber/CMakeLists.txt b/C/string_subscriber/CMakeLists.txt similarity index 100% rename from string_subscriber/CMakeLists.txt rename to C/string_subscriber/CMakeLists.txt diff --git a/string_subscriber/main.c b/C/string_subscriber/main.c similarity index 100% rename from string_subscriber/main.c rename to C/string_subscriber/main.c diff --git a/string_subscriber/package.xml b/C/string_subscriber/package.xml similarity index 100% rename from string_subscriber/package.xml rename to C/string_subscriber/package.xml diff --git a/RAD0_control/CMakeLists.txt b/Cpp/RAD0_control/CMakeLists.txt similarity index 100% rename from RAD0_control/CMakeLists.txt rename to Cpp/RAD0_control/CMakeLists.txt diff --git a/RAD0_control/README.md b/Cpp/RAD0_control/README.md similarity index 100% rename from RAD0_control/README.md rename to Cpp/RAD0_control/README.md diff --git a/RAD0_control/main.cpp b/Cpp/RAD0_control/main.cpp similarity index 100% rename from RAD0_control/main.cpp rename to Cpp/RAD0_control/main.cpp diff --git a/RAD0_control/package.xml b/Cpp/RAD0_control/package.xml similarity index 100% rename from RAD0_control/package.xml rename to Cpp/RAD0_control/package.xml From bb6273638819bbfdbd814e562b8f097e814f9e71 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Thu, 25 Oct 2018 15:54:25 +0200 Subject: [PATCH 23/27] Refs #3637 - Translate demo to rclcpp. Packages names changes in order to avoid conflicts. --- C/RAD0_actuator/CMakeLists.txt | 2 +- C/RAD0_actuator/main.c | 2 +- C/RAD0_actuator/package.xml | 2 +- C/RAD0_altitude_sensor/CMakeLists.txt | 2 +- C/RAD0_altitude_sensor/main.c | 2 +- C/RAD0_altitude_sensor/package.xml | 2 +- C/RAD0_display/CMakeLists.txt | 2 +- C/RAD0_display/main.c | 2 +- C/RAD0_display/package.xml | 2 +- C/complex_msg_publisher/CMakeLists.txt | 2 +- C/complex_msg_publisher/main.c | 2 +- C/complex_msg_publisher/package.xml | 2 +- C/complex_msg_subscriber/CMakeLists.txt | 2 +- C/complex_msg_subscriber/main.c | 2 +- C/complex_msg_subscriber/package.xml | 2 +- C/int32_publisher/CMakeLists.txt | 2 +- C/int32_publisher/main.c | 2 +- C/int32_publisher/package.xml | 2 +- C/int32_subscriber/CMakeLists.txt | 2 +- C/int32_subscriber/main.c | 2 +- C/int32_subscriber/package.xml | 2 +- C/string_publisher/CMakeLists.txt | 2 +- C/string_publisher/main.c | 2 +- C/string_publisher/package.xml | 2 +- C/string_subscriber/CMakeLists.txt | 2 +- C/string_subscriber/main.c | 2 +- C/string_subscriber/package.xml | 2 +- Cpp/RAD0_control/CMakeLists.txt | 2 +- Cpp/RAD0_control/COLCON_IGNORE | 0 Cpp/RAD0_control/main.cpp | 4 +- Cpp/RAD0_control/package.xml | 2 +- Cpp/int32_publisher/CMakeLists.txt | 40 +++++++++++++++ Cpp/int32_publisher/README.md | 0 Cpp/int32_publisher/main.cpp | 49 +++++++++++++++++++ Cpp/int32_publisher/package.xml | 23 +++++++++ {C => Messages}/complex_msg/CMakeLists.txt | 0 .../complex_msg/msg/MultiStringTest.msg | 0 .../complex_msg/msg/NestedMsgTest.msg | 0 {C => Messages}/complex_msg/package.xml | 0 README.md | 8 +-- 40 files changed, 147 insertions(+), 35 deletions(-) create mode 100644 Cpp/RAD0_control/COLCON_IGNORE create mode 100644 Cpp/int32_publisher/CMakeLists.txt create mode 100644 Cpp/int32_publisher/README.md create mode 100644 Cpp/int32_publisher/main.cpp create mode 100644 Cpp/int32_publisher/package.xml rename {C => Messages}/complex_msg/CMakeLists.txt (100%) rename {C => Messages}/complex_msg/msg/MultiStringTest.msg (100%) rename {C => Messages}/complex_msg/msg/NestedMsgTest.msg (100%) rename {C => Messages}/complex_msg/package.xml (100%) diff --git a/C/RAD0_actuator/CMakeLists.txt b/C/RAD0_actuator/CMakeLists.txt index d4e2d3d..64239c2 100644 --- a/C/RAD0_actuator/CMakeLists.txt +++ b/C/RAD0_actuator/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(rad0_actuator) +project(rad0_actuator_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/RAD0_actuator/main.c b/C/RAD0_actuator/main.c index b73847d..6c72992 100644 --- a/C/RAD0_actuator/main.c +++ b/C/RAD0_actuator/main.c @@ -41,7 +41,7 @@ int main(int argc, char* argv[]) rclc_init(0, NULL); - node = rclc_create_node("actuator", ""); + node = rclc_create_node("rad0_actuator_c", ""); ASSERT(node); engine_sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", engine_on_message, 1, false); ASSERT(engine_sub); diff --git a/C/RAD0_actuator/package.xml b/C/RAD0_actuator/package.xml index 6de1f09..98cfc69 100644 --- a/C/RAD0_actuator/package.xml +++ b/C/RAD0_actuator/package.xml @@ -1,7 +1,7 @@ - rad0_actuator + rad0_actuator_c 0.0.1 Real apliacion demostration. Actuator node Javier Moreno diff --git a/C/RAD0_altitude_sensor/CMakeLists.txt b/C/RAD0_altitude_sensor/CMakeLists.txt index 56c646f..cd2e370 100644 --- a/C/RAD0_altitude_sensor/CMakeLists.txt +++ b/C/RAD0_altitude_sensor/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(rad0_altitude_sensor) +project(rad0_altitude_sensor_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/RAD0_altitude_sensor/main.c b/C/RAD0_altitude_sensor/main.c index 8197a62..67332eb 100644 --- a/C/RAD0_altitude_sensor/main.c +++ b/C/RAD0_altitude_sensor/main.c @@ -24,7 +24,7 @@ int main(int argc, char *argv[]) rclc_node_t* node = NULL; rclc_publisher_t* publisher = NULL; - node = rclc_create_node("altitude_sensor", ""); + node = rclc_create_node("rad0_altitude_sensor_c", ""); ASSERT(node); publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64), "std_msgs_msg_Float64", 1); ASSERT(publisher); diff --git a/C/RAD0_altitude_sensor/package.xml b/C/RAD0_altitude_sensor/package.xml index 60aac8e..7355d69 100644 --- a/C/RAD0_altitude_sensor/package.xml +++ b/C/RAD0_altitude_sensor/package.xml @@ -1,7 +1,7 @@ - rad0_altitude_sensor + rad0_altitude_sensor_c 0.0.1 Real apliacion demostration. Position sensor node Javier Moreno diff --git a/C/RAD0_display/CMakeLists.txt b/C/RAD0_display/CMakeLists.txt index 7e25b98..dce8c69 100644 --- a/C/RAD0_display/CMakeLists.txt +++ b/C/RAD0_display/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(rad0_display) +project(rad0_display_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/RAD0_display/main.c b/C/RAD0_display/main.c index cdb4576..e8fe3cb 100644 --- a/C/RAD0_display/main.c +++ b/C/RAD0_display/main.c @@ -84,7 +84,7 @@ int main(int argc, char *argv[]) rclc_init(0, NULL); - node = rclc_create_node("display", ""); + node = rclc_create_node("rad0_display_c", ""); ASSERT(node); alert_subscription = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_alert_message, 1, false); ASSERT(alert_subscription); diff --git a/C/RAD0_display/package.xml b/C/RAD0_display/package.xml index b81b163..cf97535 100644 --- a/C/RAD0_display/package.xml +++ b/C/RAD0_display/package.xml @@ -1,7 +1,7 @@ - rad0_display + rad0_display_c 0.0.1 Real apliacion demostration. Display on screen any message Javier Moreno diff --git a/C/complex_msg_publisher/CMakeLists.txt b/C/complex_msg_publisher/CMakeLists.txt index b506923..f2b57f9 100644 --- a/C/complex_msg_publisher/CMakeLists.txt +++ b/C/complex_msg_publisher/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(complex_msg_publisher) +project(complex_msg_publisher_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/complex_msg_publisher/main.c b/C/complex_msg_publisher/main.c index 3e31bdb..1c49b36 100644 --- a/C/complex_msg_publisher/main.c +++ b/C/complex_msg_publisher/main.c @@ -8,7 +8,7 @@ int main(int argc, char* argv[]) (void)argc; (void)argv; rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_node_t* node = rclc_create_node("complex_msg_publisher_c", ""); if (node == NULL) { return -1; diff --git a/C/complex_msg_publisher/package.xml b/C/complex_msg_publisher/package.xml index 84d7bf0..dc11fca 100644 --- a/C/complex_msg_publisher/package.xml +++ b/C/complex_msg_publisher/package.xml @@ -1,7 +1,7 @@ - complex_msg_publisher + complex_msg_publisher_c 0.0.1 Example of a complex msg publisher Javier Moreno diff --git a/C/complex_msg_subscriber/CMakeLists.txt b/C/complex_msg_subscriber/CMakeLists.txt index 7347306..0a5a42f 100644 --- a/C/complex_msg_subscriber/CMakeLists.txt +++ b/C/complex_msg_subscriber/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(complex_msg_subscriber) +project(complex_msg_subscriber_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/complex_msg_subscriber/main.c b/C/complex_msg_subscriber/main.c index def4b0b..4dc17bf 100644 --- a/C/complex_msg_subscriber/main.c +++ b/C/complex_msg_subscriber/main.c @@ -35,7 +35,7 @@ int main(int argc, char* argv[]) (void)argc; (void)argv; rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_node_t* node = rclc_create_node("complex_msg_subscriber_c", ""); ASSERT(node); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(complex_msgs, msg, NestedMsgTest), "complex_msgs_msg_NestedMsgTest", on_message, 1, false); ASSERT(sub); diff --git a/C/complex_msg_subscriber/package.xml b/C/complex_msg_subscriber/package.xml index 59f8ec9..b599a15 100644 --- a/C/complex_msg_subscriber/package.xml +++ b/C/complex_msg_subscriber/package.xml @@ -1,7 +1,7 @@ - complex_msg_subscriber + complex_msg_subscriber_c 0.0.1 Example of a complex smg subcriber Javier Moreno diff --git a/C/int32_publisher/CMakeLists.txt b/C/int32_publisher/CMakeLists.txt index 6fc1f7c..22279a6 100644 --- a/C/int32_publisher/CMakeLists.txt +++ b/C/int32_publisher/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(int32_publisher) +project(int32_publisher_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/int32_publisher/main.c b/C/int32_publisher/main.c index 1dd7718..13462f2 100644 --- a/C/int32_publisher/main.c +++ b/C/int32_publisher/main.c @@ -10,7 +10,7 @@ int main(int argc, char *argv[]) (void)argc; (void)argv; rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_node_t* node = rclc_create_node("int32_publisher_c", ""); ASSERT(node); rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", 1); ASSERT(publisher); diff --git a/C/int32_publisher/package.xml b/C/int32_publisher/package.xml index afb1f65..9b590d8 100644 --- a/C/int32_publisher/package.xml +++ b/C/int32_publisher/package.xml @@ -1,7 +1,7 @@ - int32_publisher + int32_publisher_c 0.0.1 Example of a publisher using int32 borjaouterelo diff --git a/C/int32_subscriber/CMakeLists.txt b/C/int32_subscriber/CMakeLists.txt index de9d1f3..78eb315 100644 --- a/C/int32_subscriber/CMakeLists.txt +++ b/C/int32_subscriber/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(int32_subscriber) +project(int32_subscriber_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/int32_subscriber/main.c b/C/int32_subscriber/main.c index 62c1edc..621abc7 100644 --- a/C/int32_subscriber/main.c +++ b/C/int32_subscriber/main.c @@ -16,7 +16,7 @@ int main(int argc, char* argv[]) (void)argc; (void)argv; rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_node_t* node = rclc_create_node("int32_subscriber_c", ""); ASSERT(node); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "std_msgs_msg_Int32", on_message, 1, false); diff --git a/C/int32_subscriber/package.xml b/C/int32_subscriber/package.xml index 8adb113..f4d2b46 100644 --- a/C/int32_subscriber/package.xml +++ b/C/int32_subscriber/package.xml @@ -1,7 +1,7 @@ - int32_subscriber + int32_subscriber_c 0.0.1 Example of a subscriber using int32 borjaouterelo diff --git a/C/string_publisher/CMakeLists.txt b/C/string_publisher/CMakeLists.txt index 88fad03..05e6187 100644 --- a/C/string_publisher/CMakeLists.txt +++ b/C/string_publisher/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(string_publisher) +project(string_publisher_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/string_publisher/main.c b/C/string_publisher/main.c index 57d808e..f61a7eb 100644 --- a/C/string_publisher/main.c +++ b/C/string_publisher/main.c @@ -10,7 +10,7 @@ int main(int argc, char* argv[]) (void)argc; (void)argv; rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("publisher_node", ""); + rclc_node_t* node = rclc_create_node("string_publisher_c", ""); ASSERT(node); rclc_publisher_t* publisher = rclc_create_publisher(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", 1); diff --git a/C/string_publisher/package.xml b/C/string_publisher/package.xml index f1d76ac..7265e65 100644 --- a/C/string_publisher/package.xml +++ b/C/string_publisher/package.xml @@ -1,7 +1,7 @@ - string_publisher + string_publisher_c 0.0.1 Example of a string publisher borjaouterelo diff --git a/C/string_subscriber/CMakeLists.txt b/C/string_subscriber/CMakeLists.txt index 99a3536..c7c5356 100644 --- a/C/string_subscriber/CMakeLists.txt +++ b/C/string_subscriber/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) -project(string_subscriber) +project(string_subscriber_c) find_package(ament_cmake REQUIRED) find_package(rclc QUIET) diff --git a/C/string_subscriber/main.c b/C/string_subscriber/main.c index 556b18d..9309f3e 100644 --- a/C/string_subscriber/main.c +++ b/C/string_subscriber/main.c @@ -16,7 +16,7 @@ int main(int argc, char* argv[]) (void)argc; (void)argv; rclc_init(0, NULL); - rclc_node_t* node = rclc_create_node("subscription_node", ""); + rclc_node_t* node = rclc_create_node("string_subscriber_c", ""); ASSERT(node); rclc_subscription_t* sub = rclc_create_subscription(node, RCLC_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "std_msgs_msg_String", on_message, 1, false); diff --git a/C/string_subscriber/package.xml b/C/string_subscriber/package.xml index 24eab37..b630633 100644 --- a/C/string_subscriber/package.xml +++ b/C/string_subscriber/package.xml @@ -1,7 +1,7 @@ - string_subscriber + string_subscriber_c 0.0.1 Example of a string subscriber borjaouterelo diff --git a/Cpp/RAD0_control/CMakeLists.txt b/Cpp/RAD0_control/CMakeLists.txt index 0132cd2..93c3b27 100644 --- a/Cpp/RAD0_control/CMakeLists.txt +++ b/Cpp/RAD0_control/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) -project(rad0_control) +project(rad0_control_cpp) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) diff --git a/Cpp/RAD0_control/COLCON_IGNORE b/Cpp/RAD0_control/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/Cpp/RAD0_control/main.cpp b/Cpp/RAD0_control/main.cpp index 17d87f5..74ab558 100644 --- a/Cpp/RAD0_control/main.cpp +++ b/Cpp/RAD0_control/main.cpp @@ -1,4 +1,4 @@ -// Copyright 2016 Open Source Robotics Foundation, Inc. +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -21,7 +21,7 @@ using std::placeholders::_1; class ExternalNode : public rclcpp::Node { public: - ExternalNode() : Node("control") + ExternalNode() : Node("rad0_control_cpp") { engine_power_publisher_ = this->create_publisher("std_msgs_msg_Int32"); warn_publisher_ = this->create_publisher("std_msgs_msg_String"); diff --git a/Cpp/RAD0_control/package.xml b/Cpp/RAD0_control/package.xml index 7479744..177489b 100644 --- a/Cpp/RAD0_control/package.xml +++ b/Cpp/RAD0_control/package.xml @@ -1,7 +1,7 @@ - rad0_control + rad0_control_cpp 0.0.1 Real apliacion demostration. Javier Moreno diff --git a/Cpp/int32_publisher/CMakeLists.txt b/Cpp/int32_publisher/CMakeLists.txt new file mode 100644 index 0000000..798783f --- /dev/null +++ b/Cpp/int32_publisher/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +project(int32_publisher_cpp) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(std_msgs REQUIRED) + +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) + +target_link_libraries(${PROJECT_NAME} Threads::Threads) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/Cpp/int32_publisher/README.md b/Cpp/int32_publisher/README.md new file mode 100644 index 0000000..e69de29 diff --git a/Cpp/int32_publisher/main.cpp b/Cpp/int32_publisher/main.cpp new file mode 100644 index 0000000..4cf9698 --- /dev/null +++ b/Cpp/int32_publisher/main.cpp @@ -0,0 +1,49 @@ +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/int32.hpp" +using namespace std::chrono_literals; + +class int32_publisher_node : public rclcpp::Node +{ +public: + int32_publisher_node() : Node("int32_publisher_cpp") + { + publisher_ = this->create_publisher("std_msgs_msg_Int32"); + timer_ = this->create_wall_timer( + 500ms, std::bind(&int32_publisher_node::timer_callback, this)); + } + +private: + void timer_callback() + { + count_.data++; + publisher_->publish(count_); + } + + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::TimerBase::SharedPtr timer_; + std_msgs::msg::Int32 count_; +}; + + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/Cpp/int32_publisher/package.xml b/Cpp/int32_publisher/package.xml new file mode 100644 index 0000000..6c1b8f7 --- /dev/null +++ b/Cpp/int32_publisher/package.xml @@ -0,0 +1,23 @@ + + + + int32_publisher_cpp + 0.0.1 + Real apliacion demostration. + Javier Moreno + Apache License 2.0 + Javier Moreno + + ament_cmake + + rclcpp + std_msgs + + rclcpp + std_msgs + + + ament_cmake + + + diff --git a/C/complex_msg/CMakeLists.txt b/Messages/complex_msg/CMakeLists.txt similarity index 100% rename from C/complex_msg/CMakeLists.txt rename to Messages/complex_msg/CMakeLists.txt diff --git a/C/complex_msg/msg/MultiStringTest.msg b/Messages/complex_msg/msg/MultiStringTest.msg similarity index 100% rename from C/complex_msg/msg/MultiStringTest.msg rename to Messages/complex_msg/msg/MultiStringTest.msg diff --git a/C/complex_msg/msg/NestedMsgTest.msg b/Messages/complex_msg/msg/NestedMsgTest.msg similarity index 100% rename from C/complex_msg/msg/NestedMsgTest.msg rename to Messages/complex_msg/msg/NestedMsgTest.msg diff --git a/C/complex_msg/package.xml b/Messages/complex_msg/package.xml similarity index 100% rename from C/complex_msg/package.xml rename to Messages/complex_msg/package.xml diff --git a/README.md b/README.md index 1ca914f..1129cf1 100644 --- a/README.md +++ b/README.md @@ -213,7 +213,7 @@ For further information about this demonstration click [here]() #### Packages -##### RAD0_actuator +##### rad0_actuator The mission of this node is to simulate a dummy engine power actuator. It receives power increments and publishes the total power amount as a DDS topic. @@ -223,7 +223,7 @@ The node is built using the Micro-ROS middleware packages (rmw_micro_xrcedds and It is meant to be running in a microcontroller processor, but for this demonstration, the node runs on the host PC. The node is connected to the DDS world through a Micro XRCE-DDS Agent. -##### RAD0_altitude_sensor +##### rad0_altitude_sensor The mission of this node is to simulate a dummy altitude sensor. It publishes the altitude variations as a DDS topic. @@ -233,7 +233,7 @@ The node is built using the Micro-ROS middleware packages (rmw_micro_xrcedds and It is meant to be running in a microcontroller processor, but for this demonstration, the node runs on the host PC. The node is connected to the DDS world through a Micro XRCE-DDS Agent. -##### RAD0_control +##### rad0_control The mission of this node is to read altitude values and send to the actuator engine variations. It also publishes the status (OK, WARNING or FAILURE) as a DDS topic. @@ -243,7 +243,7 @@ The node is built using the ROS 2 middleware packages (rmw_fastrtps and rosidl_t It is meant to be running in on a regular PC, and it is directly connected to de DDS world. -##### RAD0_display +##### rad0_display The mission of this node is to simulate one LCD screen that prints the critical parameters. It subscribes to the altitude, power and status messages available as a DDS topic. From 58d56672bc1c9dedd06aa65885672a7f65c70f30 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Sat, 27 Oct 2018 17:48:17 +0200 Subject: [PATCH 24/27] Refs #3637 - Translate demo to rclcpp. Traslate int32 pub/sub demos (works ok). --- Cpp/RAD0_control/README.md | 0 Cpp/int32_publisher/main.cpp | 2 ++ Cpp/int32_publisher/package.xml | 2 +- Cpp/int32_subscriber/CMakeLists.txt | 40 +++++++++++++++++++++++++ Cpp/int32_subscriber/main.cpp | 45 +++++++++++++++++++++++++++++ Cpp/int32_subscriber/package.xml | 23 +++++++++++++++ 6 files changed, 111 insertions(+), 1 deletion(-) delete mode 100644 Cpp/RAD0_control/README.md create mode 100644 Cpp/int32_subscriber/CMakeLists.txt create mode 100644 Cpp/int32_subscriber/main.cpp create mode 100644 Cpp/int32_subscriber/package.xml diff --git a/Cpp/RAD0_control/README.md b/Cpp/RAD0_control/README.md deleted file mode 100644 index e69de29..0000000 diff --git a/Cpp/int32_publisher/main.cpp b/Cpp/int32_publisher/main.cpp index 4cf9698..a3c104e 100644 --- a/Cpp/int32_publisher/main.cpp +++ b/Cpp/int32_publisher/main.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/int32.hpp" using namespace std::chrono_literals; @@ -32,6 +33,7 @@ class int32_publisher_node : public rclcpp::Node { count_.data++; publisher_->publish(count_); + std::cout << count_.data << std::endl; } rclcpp::Publisher::SharedPtr publisher_; diff --git a/Cpp/int32_publisher/package.xml b/Cpp/int32_publisher/package.xml index 6c1b8f7..98e2db8 100644 --- a/Cpp/int32_publisher/package.xml +++ b/Cpp/int32_publisher/package.xml @@ -3,7 +3,7 @@ int32_publisher_cpp 0.0.1 - Real apliacion demostration. + Example of a publisher using int32 Javier Moreno Apache License 2.0 Javier Moreno diff --git a/Cpp/int32_subscriber/CMakeLists.txt b/Cpp/int32_subscriber/CMakeLists.txt new file mode 100644 index 0000000..bc4537f --- /dev/null +++ b/Cpp/int32_subscriber/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +project(int32_subscriber_cpp) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(std_msgs REQUIRED) + +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) + +target_link_libraries(${PROJECT_NAME} Threads::Threads) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/Cpp/int32_subscriber/main.cpp b/Cpp/int32_subscriber/main.cpp new file mode 100644 index 0000000..1dcba12 --- /dev/null +++ b/Cpp/int32_subscriber/main.cpp @@ -0,0 +1,45 @@ +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/int32.hpp" +using std::placeholders::_1; + +class int32_subscriber_node : public rclcpp::Node +{ +public: + int32_subscriber_node() : Node("int32_subscriber_cpp") + { + subscription_ = this->create_subscription("std_msgs_msg_Int32", + std::bind(&int32_subscriber_node::topic_callback, this, _1)); + } + +private: + rclcpp::Subscription::SharedPtr subscription_; + + void topic_callback(const std_msgs::msg::Int32::SharedPtr msg) + { + std::cout << "I heard: " << msg->data << std::endl; + } +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/Cpp/int32_subscriber/package.xml b/Cpp/int32_subscriber/package.xml new file mode 100644 index 0000000..c7ec0d6 --- /dev/null +++ b/Cpp/int32_subscriber/package.xml @@ -0,0 +1,23 @@ + + + + int32_subscriber_cpp + 0.0.1 + Example of a subscriber using int32 + Javier Moreno + Apache License 2.0 + Javier Moreno + + ament_cmake + + rclcpp + std_msgs + + rclcpp + std_msgs + + + ament_cmake + + + From 641aa2b83385e30fa6fe1bfc478448057ef3a6a8 Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Sun, 28 Oct 2018 09:36:58 +0100 Subject: [PATCH 25/27] Refs #3637 - Translate demo to rclcpp. Traslate string and complex_msg pub/sub demos. --- Cpp/RAD0_control/CMakeLists.txt | 4 + Cpp/RAD0_control/COLCON_IGNORE | 0 Cpp/complex_msg_publisher/CMakeLists.txt | 40 ++++++++++ Cpp/complex_msg_publisher/main.cpp | 90 +++++++++++++++++++++++ Cpp/complex_msg_publisher/package.xml | 16 ++++ Cpp/complex_msg_subscriber/CMakeLists.txt | 40 ++++++++++ Cpp/complex_msg_subscriber/main.cpp | 63 ++++++++++++++++ Cpp/complex_msg_subscriber/package.xml | 16 ++++ Cpp/int32_publisher/README.md | 0 Cpp/string_publisher/CMakeLists.txt | 40 ++++++++++ Cpp/string_publisher/main.cpp | 52 +++++++++++++ Cpp/string_publisher/package.xml | 16 ++++ Cpp/string_subscriber/CMakeLists.txt | 40 ++++++++++ Cpp/string_subscriber/main.cpp | 44 +++++++++++ Cpp/string_subscriber/package.xml | 16 ++++ 15 files changed, 477 insertions(+) delete mode 100644 Cpp/RAD0_control/COLCON_IGNORE create mode 100644 Cpp/complex_msg_publisher/CMakeLists.txt create mode 100644 Cpp/complex_msg_publisher/main.cpp create mode 100644 Cpp/complex_msg_publisher/package.xml create mode 100644 Cpp/complex_msg_subscriber/CMakeLists.txt create mode 100644 Cpp/complex_msg_subscriber/main.cpp create mode 100644 Cpp/complex_msg_subscriber/package.xml delete mode 100644 Cpp/int32_publisher/README.md create mode 100644 Cpp/string_publisher/CMakeLists.txt create mode 100644 Cpp/string_publisher/main.cpp create mode 100644 Cpp/string_publisher/package.xml create mode 100644 Cpp/string_subscriber/CMakeLists.txt create mode 100644 Cpp/string_subscriber/main.cpp create mode 100644 Cpp/string_subscriber/package.xml diff --git a/Cpp/RAD0_control/CMakeLists.txt b/Cpp/RAD0_control/CMakeLists.txt index 93c3b27..de22bdc 100644 --- a/Cpp/RAD0_control/CMakeLists.txt +++ b/Cpp/RAD0_control/CMakeLists.txt @@ -15,6 +15,8 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(std_msgs REQUIRED) +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) @@ -27,6 +29,8 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) +target_link_libraries(${PROJECT_NAME} Threads::Threads) + install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/RAD0_control/COLCON_IGNORE b/Cpp/RAD0_control/COLCON_IGNORE deleted file mode 100644 index e69de29..0000000 diff --git a/Cpp/complex_msg_publisher/CMakeLists.txt b/Cpp/complex_msg_publisher/CMakeLists.txt new file mode 100644 index 0000000..42f2799 --- /dev/null +++ b/Cpp/complex_msg_publisher/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +project(complex_msg_publisher_cpp) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(complex_msgs REQUIRED) + +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp complex_msgs) + +target_link_libraries(${PROJECT_NAME} Threads::Threads) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/Cpp/complex_msg_publisher/main.cpp b/Cpp/complex_msg_publisher/main.cpp new file mode 100644 index 0000000..484f3c4 --- /dev/null +++ b/Cpp/complex_msg_publisher/main.cpp @@ -0,0 +1,90 @@ +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +using namespace std::chrono_literals; + +class complex_msg_publisher_cpp_node : public rclcpp::Node +{ +public: + complex_msg_publisher_cpp_node() : Node("complex_msg_publisher_cpp") + { + publisher_ = this->create_publisher("complex_msgs_msg_NestedMsgTest"); + timer_ = this->create_wall_timer( + 500ms, std::bind(&complex_msg_publisher_cpp_node::timer_callback, this)); + } + +private: + void timer_callback() + { + msg.data1 = (bool)(num & 0x01); + msg.data2 = (uint8_t)num; + msg.data3 = (signed char)num; + msg.data4 = (float)num; + msg.data5 = (double)num; + msg.data6 = (int8_t)num; + msg.data7 = (uint8_t)num; + msg.data8 = (int16_t)num; + msg.data9 = (uint16_t)num; + msg.data10 = (int32_t)num; + msg.data11 = (uint32_t)num; + msg.data12 = (int64_t)num; + msg.data13 = (uint64_t)num; + msg.data14.data1 = "Msg A - " + std::to_string(num); + msg.data14.data2 = "Msg B - " + std::to_string(num); + msg.data14.data3 = "Msg C - " + std::to_string(num); + msg.data14.data4 = "Msg D - " + std::to_string(num); + num++; + + publisher_->publish(msg); + + std::cout << "I send:" << std::endl; + std::cout << "\tBool: " << std::to_string(msg.data1) << std::endl; + std::cout << "\tuint8_t: " << std::to_string(msg.data2) << std::endl; + std::cout << "\tsigned char: " << std::to_string(msg.data3) << std::endl; + std::cout << "\tfloat: " << std::to_string(msg.data4) << std::endl; + std::cout << "\tdouble: " << std::to_string(msg.data5) << std::endl; + std::cout << "\tint8_t: " << std::to_string(msg.data6) << std::endl; + std::cout << "\tuint8_t: " << std::to_string(msg.data7) << std::endl; + std::cout << "\tint16_t: " << std::to_string(msg.data8) << std::endl; + std::cout << "\tuint16_t: " << std::to_string(msg.data9) << std::endl; + std::cout << "\tint32_t: " << std::to_string(msg.data10) << std::endl; + std::cout << "\tuint32_t: " << std::to_string(msg.data11) << std::endl; + std::cout << "\tint64_t: " << std::to_string(msg.data12) << std::endl; + std::cout << "\tuint64_t: " << std::to_string(msg.data13) << std::endl; + + std::cout << "\tstring 1: " << msg.data14.data1 << std::endl; + std::cout << "\tstring 2: " << msg.data14.data2 << std::endl; + std::cout << "\tstring 3: " << msg.data14.data3 << std::endl; + std::cout << "\tstring 4: " << msg.data14.data4 << std::endl; + std::cout << "\n" << std::endl; + } + + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::TimerBase::SharedPtr timer_; + complex_msgs::msg::NestedMsgTest msg; + size_t num = 0; +}; + + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/Cpp/complex_msg_publisher/package.xml b/Cpp/complex_msg_publisher/package.xml new file mode 100644 index 0000000..a86227c --- /dev/null +++ b/Cpp/complex_msg_publisher/package.xml @@ -0,0 +1,16 @@ + + + + complex_msg_publisher_cpp + 0.0.1 + Example of a complex msg publisher + Javier Moreno + Apache License 2.0 + ament_cmake + rclcpp + complex_msgs + + ament_cmake + + + diff --git a/Cpp/complex_msg_subscriber/CMakeLists.txt b/Cpp/complex_msg_subscriber/CMakeLists.txt new file mode 100644 index 0000000..1ee7782 --- /dev/null +++ b/Cpp/complex_msg_subscriber/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +project(complex_msg_subscriber_cpp) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(complex_msgs REQUIRED) + +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp complex_msgs) + +target_link_libraries(${PROJECT_NAME} Threads::Threads) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/Cpp/complex_msg_subscriber/main.cpp b/Cpp/complex_msg_subscriber/main.cpp new file mode 100644 index 0000000..28bd114 --- /dev/null +++ b/Cpp/complex_msg_subscriber/main.cpp @@ -0,0 +1,63 @@ +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include "rclcpp/rclcpp.hpp" +using std::placeholders::_1; + +class complex_msg_subscriber_cpp_node : public rclcpp::Node +{ +public: + complex_msg_subscriber_cpp_node() : Node("complex_msg_subscriber_cpp") + { + subscription_ = this->create_subscription("complex_msgs_msg_NestedMsgTest", + std::bind(&complex_msg_subscriber_cpp_node::topic_callback, this, _1)); + } + +private: + rclcpp::Subscription::SharedPtr subscription_; + + void topic_callback(const complex_msgs::msg::NestedMsgTest::SharedPtr msg) + { + std::cout << "I heard: " << std::endl; + std::cout << "\tBool: " << std::to_string(msg->data1) << std::endl; + std::cout << "\tuint8_t: " << std::to_string(msg->data2) << std::endl; + std::cout << "\tsigned char: " << std::to_string(msg->data3) << std::endl; + std::cout << "\tfloat: " << std::to_string(msg->data4) << std::endl; + std::cout << "\tdouble: " << std::to_string(msg->data5) << std::endl; + std::cout << "\tint8_t: " << std::to_string(msg->data6) << std::endl; + std::cout << "\tuint8_t: " << std::to_string(msg->data7) << std::endl; + std::cout << "\tint16_t: " << std::to_string(msg->data8) << std::endl; + std::cout << "\tuint16_t: " << std::to_string(msg->data9) << std::endl; + std::cout << "\tint32_t: " << std::to_string(msg->data10) << std::endl; + std::cout << "\tuint32_t: " << std::to_string(msg->data11) << std::endl; + std::cout << "\tint64_t: " << std::to_string(msg->data12) << std::endl; + std::cout << "\tuint64_t: " << std::to_string(msg->data13) << std::endl; + + std::cout << "\tstring 1: " << msg->data14.data1 << std::endl; + std::cout << "\tstring 2: " << msg->data14.data2 << std::endl; + std::cout << "\tstring 3: " << msg->data14.data3 << std::endl; + std::cout << "\tstring 4: " << msg->data14.data4 << std::endl; + std::cout << "\n" << std::endl; + } +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/Cpp/complex_msg_subscriber/package.xml b/Cpp/complex_msg_subscriber/package.xml new file mode 100644 index 0000000..9402eec --- /dev/null +++ b/Cpp/complex_msg_subscriber/package.xml @@ -0,0 +1,16 @@ + + + + complex_msg_subscriber_cpp + 0.0.1 + Example of a complex smg subcriber + Javier Moreno + Apache License 2.0 + ament_cmake + rclcpp + complex_msgs + + ament_cmake + + + diff --git a/Cpp/int32_publisher/README.md b/Cpp/int32_publisher/README.md deleted file mode 100644 index e69de29..0000000 diff --git a/Cpp/string_publisher/CMakeLists.txt b/Cpp/string_publisher/CMakeLists.txt new file mode 100644 index 0000000..0d162b3 --- /dev/null +++ b/Cpp/string_publisher/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +project(string_publisher_cpp) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(std_msgs REQUIRED) + +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) + +target_link_libraries(${PROJECT_NAME} Threads::Threads) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/Cpp/string_publisher/main.cpp b/Cpp/string_publisher/main.cpp new file mode 100644 index 0000000..a696ce2 --- /dev/null +++ b/Cpp/string_publisher/main.cpp @@ -0,0 +1,52 @@ +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +using namespace std::chrono_literals; + +class string_publisher_cpp_node : public rclcpp::Node +{ +public: + string_publisher_cpp_node() : Node("string_publisher_cpp") + { + publisher_ = this->create_publisher("std_msgs_msg_String"); + timer_ = this->create_wall_timer( + 500ms, std::bind(&string_publisher_cpp_node::timer_callback, this)); + } + +private: + void timer_callback() + { + msg.data = "Hello World " + std::to_string(num++); + publisher_->publish(msg); + std::cout << msg.data << std::endl; + } + + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::TimerBase::SharedPtr timer_; + std_msgs::msg::String msg; + size_t num = 0; +}; + + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/Cpp/string_publisher/package.xml b/Cpp/string_publisher/package.xml new file mode 100644 index 0000000..38a7705 --- /dev/null +++ b/Cpp/string_publisher/package.xml @@ -0,0 +1,16 @@ + + + + string_publisher_cpp + 0.0.1 + Example of a string publisher + borjaouterelo + Apache License 2.0 + ament_cmake + rclcpp + std_msgs + + ament_cmake + + + diff --git a/Cpp/string_subscriber/CMakeLists.txt b/Cpp/string_subscriber/CMakeLists.txt new file mode 100644 index 0000000..462b447 --- /dev/null +++ b/Cpp/string_subscriber/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +project(string_subscriber_cpp) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp QUIET) +find_package(std_msgs REQUIRED) + +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package (Threads REQUIRED) + + +# Do not compile package if rclcpp is not found +if (NOT rclcpp_FOUND) + message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") + ament_package() + return() +endif() + + +add_executable(${PROJECT_NAME} main.cpp) +ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) + +target_link_libraries(${PROJECT_NAME} Threads::Threads) + +install(TARGETS + ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/Cpp/string_subscriber/main.cpp b/Cpp/string_subscriber/main.cpp new file mode 100644 index 0000000..74eca5c --- /dev/null +++ b/Cpp/string_subscriber/main.cpp @@ -0,0 +1,44 @@ +// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include "rclcpp/rclcpp.hpp" +using std::placeholders::_1; + +class string_subscriber_cpp_node : public rclcpp::Node +{ +public: + string_subscriber_cpp_node() : Node("string_subscriber_cpp") + { + subscription_ = this->create_subscription("std_msgs_msg_String", + std::bind(&string_subscriber_cpp_node::topic_callback, this, _1)); + } + +private: + rclcpp::Subscription::SharedPtr subscription_; + + void topic_callback(const std_msgs::msg::String::SharedPtr msg) + { + std::cout << "I heard: " << msg->data << std::endl; + } +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/Cpp/string_subscriber/package.xml b/Cpp/string_subscriber/package.xml new file mode 100644 index 0000000..568cddf --- /dev/null +++ b/Cpp/string_subscriber/package.xml @@ -0,0 +1,16 @@ + + + + string_subscriber_cpp + 0.0.1 + Example of a string subscriber + borjaouterelo + Apache License 2.0 + ament_cmake + rclcpp + std_msgs + + ament_cmake + + + From 85a207c321b7d7a86a7f799dc55a78a8001b856a Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Tue, 30 Oct 2018 07:47:32 +0100 Subject: [PATCH 26/27] Removed pthread dependency. --- Cpp/RAD0_control/CMakeLists.txt | 5 ----- Cpp/complex_msg_publisher/CMakeLists.txt | 6 ------ Cpp/complex_msg_subscriber/CMakeLists.txt | 5 ----- Cpp/int32_publisher/CMakeLists.txt | 5 ----- Cpp/int32_subscriber/CMakeLists.txt | 5 ----- Cpp/string_publisher/CMakeLists.txt | 5 ----- Cpp/string_subscriber/CMakeLists.txt | 5 ----- 7 files changed, 36 deletions(-) diff --git a/Cpp/RAD0_control/CMakeLists.txt b/Cpp/RAD0_control/CMakeLists.txt index de22bdc..5a77197 100644 --- a/Cpp/RAD0_control/CMakeLists.txt +++ b/Cpp/RAD0_control/CMakeLists.txt @@ -15,9 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(std_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") @@ -29,8 +26,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/complex_msg_publisher/CMakeLists.txt b/Cpp/complex_msg_publisher/CMakeLists.txt index 42f2799..aa680a5 100644 --- a/Cpp/complex_msg_publisher/CMakeLists.txt +++ b/Cpp/complex_msg_publisher/CMakeLists.txt @@ -15,10 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(complex_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) message(WARNING "${PROJECT_NAME} will be ignored due to rclcpp is not installed") @@ -30,8 +26,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp complex_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/complex_msg_subscriber/CMakeLists.txt b/Cpp/complex_msg_subscriber/CMakeLists.txt index 1ee7782..5f547f2 100644 --- a/Cpp/complex_msg_subscriber/CMakeLists.txt +++ b/Cpp/complex_msg_subscriber/CMakeLists.txt @@ -15,9 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(complex_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) @@ -30,8 +27,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp complex_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/int32_publisher/CMakeLists.txt b/Cpp/int32_publisher/CMakeLists.txt index 798783f..550b0c0 100644 --- a/Cpp/int32_publisher/CMakeLists.txt +++ b/Cpp/int32_publisher/CMakeLists.txt @@ -15,9 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(std_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) @@ -30,8 +27,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/int32_subscriber/CMakeLists.txt b/Cpp/int32_subscriber/CMakeLists.txt index bc4537f..3c39210 100644 --- a/Cpp/int32_subscriber/CMakeLists.txt +++ b/Cpp/int32_subscriber/CMakeLists.txt @@ -15,9 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(std_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) @@ -30,8 +27,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/string_publisher/CMakeLists.txt b/Cpp/string_publisher/CMakeLists.txt index 0d162b3..529e57d 100644 --- a/Cpp/string_publisher/CMakeLists.txt +++ b/Cpp/string_publisher/CMakeLists.txt @@ -15,9 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(std_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) @@ -30,8 +27,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} diff --git a/Cpp/string_subscriber/CMakeLists.txt b/Cpp/string_subscriber/CMakeLists.txt index 462b447..69309d4 100644 --- a/Cpp/string_subscriber/CMakeLists.txt +++ b/Cpp/string_subscriber/CMakeLists.txt @@ -15,9 +15,6 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp QUIET) find_package(std_msgs REQUIRED) -set(THREADS_PREFER_PTHREAD_FLAG TRUE) -find_package (Threads REQUIRED) - # Do not compile package if rclcpp is not found if (NOT rclcpp_FOUND) @@ -30,8 +27,6 @@ endif() add_executable(${PROJECT_NAME} main.cpp) ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs) -target_link_libraries(${PROJECT_NAME} Threads::Threads) - install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME} From fce5d1a9c7d188ea8e5087675b4a1d0f2e83baff Mon Sep 17 00:00:00 2001 From: Javier Moreno Date: Mon, 5 Nov 2018 10:46:50 +0100 Subject: [PATCH 27/27] Changes applied according to disscusion. --- Cpp/RAD0_control/CMakeLists.txt | 2 +- Cpp/complex_msg_publisher/CMakeLists.txt | 2 +- Cpp/complex_msg_subscriber/CMakeLists.txt | 2 +- Cpp/int32_publisher/CMakeLists.txt | 2 +- Cpp/int32_subscriber/CMakeLists.txt | 2 +- Cpp/string_publisher/CMakeLists.txt | 2 +- Cpp/string_subscriber/CMakeLists.txt | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Cpp/RAD0_control/CMakeLists.txt b/Cpp/RAD0_control/CMakeLists.txt index 5a77197..65dc08f 100644 --- a/Cpp/RAD0_control/CMakeLists.txt +++ b/Cpp/RAD0_control/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(rad0_control_cpp) # Default to C++14 diff --git a/Cpp/complex_msg_publisher/CMakeLists.txt b/Cpp/complex_msg_publisher/CMakeLists.txt index aa680a5..010345e 100644 --- a/Cpp/complex_msg_publisher/CMakeLists.txt +++ b/Cpp/complex_msg_publisher/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(complex_msg_publisher_cpp) # Default to C++14 diff --git a/Cpp/complex_msg_subscriber/CMakeLists.txt b/Cpp/complex_msg_subscriber/CMakeLists.txt index 5f547f2..66c88d1 100644 --- a/Cpp/complex_msg_subscriber/CMakeLists.txt +++ b/Cpp/complex_msg_subscriber/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(complex_msg_subscriber_cpp) # Default to C++14 diff --git a/Cpp/int32_publisher/CMakeLists.txt b/Cpp/int32_publisher/CMakeLists.txt index 550b0c0..2eca54f 100644 --- a/Cpp/int32_publisher/CMakeLists.txt +++ b/Cpp/int32_publisher/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(int32_publisher_cpp) # Default to C++14 diff --git a/Cpp/int32_subscriber/CMakeLists.txt b/Cpp/int32_subscriber/CMakeLists.txt index 3c39210..01c8cea 100644 --- a/Cpp/int32_subscriber/CMakeLists.txt +++ b/Cpp/int32_subscriber/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(int32_subscriber_cpp) # Default to C++14 diff --git a/Cpp/string_publisher/CMakeLists.txt b/Cpp/string_publisher/CMakeLists.txt index 529e57d..b671959 100644 --- a/Cpp/string_publisher/CMakeLists.txt +++ b/Cpp/string_publisher/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(string_publisher_cpp) # Default to C++14 diff --git a/Cpp/string_subscriber/CMakeLists.txt b/Cpp/string_subscriber/CMakeLists.txt index 69309d4..3a491c1 100644 --- a/Cpp/string_subscriber/CMakeLists.txt +++ b/Cpp/string_subscriber/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -set(CMAKE_C_CLANG_TIDY clang-tidy -checks=*) +set(CMAKE_CXX_CLANG_TIDY clang-tidy -checks=*) project(string_subscriber_cpp) # Default to C++14