diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml new file mode 100644 index 0000000..1e94ff9 --- /dev/null +++ b/.github/workflows/ci.yml @@ -0,0 +1,33 @@ +name: CI + +on: + pull_request: + branches: + - '**' + +jobs: + micro_ros_demos: + runs-on: ubuntu-20.04 + container: microros/base:foxy + defaults: + run: + shell: bash + + steps: + - name: Download environment + run: | + cd /uros_ws + apt update + source /opt/ros/foxy/setup.bash + source install/local_setup.bash + ros2 run micro_ros_setup create_firmware_ws.sh host + rm -rf uros/micro-ROS-demos + - uses: actions/checkout@v2 + with: + path: uros/micro-ROS-demos + - name: Build + run: | + cd /uros_ws + source /opt/ros/foxy/setup.bash + source install/local_setup.bash + ros2 run micro_ros_setup build_firmware.sh \ No newline at end of file diff --git a/rclc/addtwoints_client/main.c b/rclc/addtwoints_client/main.c index 01451f4..bcaeb13 100644 --- a/rclc/addtwoints_client/main.c +++ b/rclc/addtwoints_client/main.c @@ -40,9 +40,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor; RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 10; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_client(&executor, &client, &res, client_callback)); int64_t seq; diff --git a/rclc/addtwoints_server/main.c b/rclc/addtwoints_server/main.c index d7b91a3..204e39a 100644 --- a/rclc/addtwoints_server/main.c +++ b/rclc/addtwoints_server/main.c @@ -8,11 +8,8 @@ #include #include -#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Aborting.\n",__LINE__,(int)temp_rc); return 1;}} -#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Continuing.\n",__LINE__,(int)temp_rc);}} - -example_interfaces__srv__AddTwoInts_Request req; -example_interfaces__srv__AddTwoInts_Response res; +#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printk("Failed status on line %d: %d. Aborting.\n",__LINE__,(int)temp_rc);}} +#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printk("Failed status on line %d: %d. Continuing.\n",__LINE__,(int)temp_rc);}} void service_callback(const void * req, void * res){ example_interfaces__srv__AddTwoInts_Request * req_in = (example_interfaces__srv__AddTwoInts_Request *) req; @@ -23,35 +20,32 @@ void service_callback(const void * req, void * res){ res_in->sum = req_in->a + req_in->b; } -int main(int argc, const char * const * argv) -{ - RCLC_UNUSED(argc); - RCLC_UNUSED(argv); - rcl_allocator_t allocator = rcl_get_default_allocator(); - rclc_support_t support; - - // create init_options - RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); +void main(void) +{ + rcl_allocator_t allocator = rcl_get_default_allocator(); - // create node - rcl_node_t node; - RCCHECK(rclc_node_init_default(&node, "add_twoints_client_rclc", "", &support)); + // create init_options + rclc_support_t support; + RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); - // create service - rcl_service_t service; - RCCHECK(rclc_service_init_default(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints")); + // create node + rcl_node_t node; + RCCHECK(rclc_node_init_default(&node, "add_twoints_client_rclc", "", &support)); - // create executor - rclc_executor_t executor; - RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); + // create service + rcl_service_t service; + RCCHECK(rclc_service_init_default(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints")); - unsigned int rcl_wait_timeout = 10; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); + // create executor + rclc_executor_t executor; + RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - RCCHECK(rclc_executor_add_service(&executor, &service, &req, &res, service_callback)); + example_interfaces__srv__AddTwoInts_Response res; + example_interfaces__srv__AddTwoInts_Request req; + RCCHECK(rclc_executor_add_service(&executor, &service, &req, &res, service_callback)); - rclc_executor_spin(&executor); + rclc_executor_spin(&executor); - RCCHECK(rcl_service_fini(&service, &node)); - RCCHECK(rcl_node_fini(&node)); + RCCHECK(rcl_service_fini(&service, &node)); + RCCHECK(rcl_node_fini(&node)); } diff --git a/rclc/autodiscover_agent/main.c b/rclc/autodiscover_agent/main.c index efca945..8685b59 100644 --- a/rclc/autodiscover_agent/main.c +++ b/rclc/autodiscover_agent/main.c @@ -67,9 +67,6 @@ int main() // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); msg.data = 0; diff --git a/rclc/configuration_example/configured_publisher/main.c b/rclc/configuration_example/configured_publisher/main.c index 943b1a4..e7a2334 100644 --- a/rclc/configuration_example/configured_publisher/main.c +++ b/rclc/configuration_example/configured_publisher/main.c @@ -73,9 +73,6 @@ int main(int argc, char * const argv[]) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); msg.data = 0; diff --git a/rclc/configuration_example/configured_subscriber/main.c b/rclc/configuration_example/configured_subscriber/main.c index 7925ce9..8944950 100644 --- a/rclc/configuration_example/configured_subscriber/main.c +++ b/rclc/configuration_example/configured_subscriber/main.c @@ -60,9 +60,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA)); rclc_executor_spin(&executor); diff --git a/rclc/fragmented_publication/main.c b/rclc/fragmented_publication/main.c index 94c0da0..63a8c45 100644 --- a/rclc/fragmented_publication/main.c +++ b/rclc/fragmented_publication/main.c @@ -56,9 +56,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); // Fill the array with a known sequence diff --git a/rclc/fragmented_subscription/main.c b/rclc/fragmented_subscription/main.c index 3a4073f..190eba0 100644 --- a/rclc/fragmented_subscription/main.c +++ b/rclc/fragmented_subscription/main.c @@ -47,9 +47,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA)); msg.data.data = (char * ) malloc(ARRAY_LEN * sizeof(char)); diff --git a/rclc/int32_multinode/main.c b/rclc/int32_multinode/main.c index 6040bd2..22a63b6 100644 --- a/rclc/int32_multinode/main.c +++ b/rclc/int32_multinode/main.c @@ -91,8 +91,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor_1 = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor_1, &support.context, 2, &allocator)); - - RCCHECK(rclc_executor_set_timeout(&executor_1, RCL_MS_TO_NS(1000))); RCCHECK(rclc_executor_add_timer(&executor_1, &timer_1)); RCCHECK(rclc_executor_add_subscription(&executor_1, &subscriber_1, &recv_msg_1, &subscription_callback_1, ON_NEW_DATA)); @@ -126,8 +124,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor_2 = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor_2, &support.context, 2, &allocator)); - - RCCHECK(rclc_executor_set_timeout(&executor_2, RCL_MS_TO_NS(1000))); RCCHECK(rclc_executor_add_timer(&executor_2, &timer_2)); RCCHECK(rclc_executor_add_subscription(&executor_2, &subscriber_2, &recv_msg_2, &subscription_callback_2, ON_NEW_DATA)); diff --git a/rclc/int32_publisher/main.c b/rclc/int32_publisher/main.c index 36d2070..4d3eda8 100644 --- a/rclc/int32_publisher/main.c +++ b/rclc/int32_publisher/main.c @@ -55,9 +55,6 @@ int main() // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); msg.data = 0; diff --git a/rclc/int32_publisher_subscriber/main.c b/rclc/int32_publisher_subscriber/main.c index 7d91bae..4b26cbc 100644 --- a/rclc/int32_publisher_subscriber/main.c +++ b/rclc/int32_publisher_subscriber/main.c @@ -69,9 +69,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 2, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &recv_msg, &subscription_callback, ON_NEW_DATA)); diff --git a/rclc/int32_subscriber/main.c b/rclc/int32_subscriber/main.c index ee0764f..d3293cf 100644 --- a/rclc/int32_subscriber/main.c +++ b/rclc/int32_subscriber/main.c @@ -41,9 +41,6 @@ int main() // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA)); rclc_executor_spin(&executor); diff --git a/rclc/ping_pong/main.c b/rclc/ping_pong/main.c index cabaf6b..4e4d875 100644 --- a/rclc/ping_pong/main.c +++ b/rclc/ping_pong/main.c @@ -106,9 +106,6 @@ int main() // Create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 3, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); RCCHECK(rclc_executor_add_subscription(&executor, &ping_subscriber, &incoming_ping, &ping_subscription_callback, ON_NEW_DATA)); RCCHECK(rclc_executor_add_subscription(&executor, &pong_subscriber, &incoming_pong, &pong_subscription_callback, ON_NEW_DATA)); diff --git a/rclc/string_publisher/main.c b/rclc/string_publisher/main.c index 4830e88..7cd7fbb 100644 --- a/rclc/string_publisher/main.c +++ b/rclc/string_publisher/main.c @@ -60,9 +60,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); // Fill the array with a known sequence diff --git a/rclc/string_subscriber/main.c b/rclc/string_subscriber/main.c index ac33f50..654fc7b 100644 --- a/rclc/string_subscriber/main.c +++ b/rclc/string_subscriber/main.c @@ -46,9 +46,6 @@ int main(int argc, const char * const * argv) // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA)); msg.data.data = (char * ) malloc(ARRAY_LEN * sizeof(char)); diff --git a/rclc/timer/main.c b/rclc/timer/main.c index 3640ac6..33ba4c0 100644 --- a/rclc/timer/main.c +++ b/rclc/timer/main.c @@ -40,9 +40,6 @@ int main() // create executor rclc_executor_t executor = rclc_executor_get_zero_initialized_executor(); RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); - - unsigned int rcl_wait_timeout = 1000; // in ms - RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout))); RCCHECK(rclc_executor_add_timer(&executor, &timer)); rclc_executor_spin(&executor);