Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update domain_id API #32

Merged
merged 2 commits into from
Nov 3, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 7 additions & 5 deletions e2studio_project_freeRTOS/src/net_thread_entry.c
Original file line number Diff line number Diff line change
Expand Up @@ -132,13 +132,15 @@ void send_micro_ros_profiling_data(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create nodes
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "profiling_node", "", &support, &node_ops);
rclc_node_init_default(&node, "profiling_node", "", &support);

// create publisher
rcl_publisher_t publisher;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,13 @@ void microros_app(void)
//create init_options
rclc_support_t support;

rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create node
rcl_node_t node;
// create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publisher
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,15 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create nodes
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publisher
rcl_publisher_t publisher;
Expand Down
76 changes: 39 additions & 37 deletions test/micro_ros_renesas_testbench/client_tests/Domain.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,11 @@ std_msgs__msg__Int32 msg;

void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
(void) last_call_time;
if (timer != NULL) {
rcl_publish(&publisher, &msg, NULL);
msg.data++;
}
(void) last_call_time;
if (timer != NULL) {
rcl_publish(&publisher, &msg, NULL);
msg.data++;
}
}

void microros_app(void)
Expand All @@ -36,38 +36,40 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);

// create publisher
rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"test_publisher_domain");

// create timer,
rcl_timer_t timer;
const unsigned int timer_timeout = 1000;
rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback);

// create executor
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
rclc_executor_init(&executor, &support.context, 1, &allocator);
rclc_executor_add_timer(&executor, &timer);

msg.data = 0;

for(;;){

rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publisher
rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"test_publisher_domain");

// create timer,
rcl_timer_t timer;
const unsigned int timer_timeout = 1000;
rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback);

// create executor
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
rclc_executor_init(&executor, &support.context, 1, &allocator);
rclc_executor_add_timer(&executor, &timer);

msg.data = 0;

for(;;){
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
sleep_ms(10);
}
Expand Down
13 changes: 7 additions & 6 deletions test/micro_ros_renesas_testbench/client_tests/EntitiesQoS.c
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,15 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publisher reliable
rcl_publisher_t publisher_reliable;
Expand Down
10 changes: 6 additions & 4 deletions test/micro_ros_renesas_testbench/client_tests/EntityCreation.c
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,11 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create nodes
rcl_node_t nodes[ENTITY_NUMBER];
Expand All @@ -29,9 +33,7 @@ void microros_app(void)
snprintf(buf_namespace, 100, "ns_%d", i);

// create node
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&nodes[i], buf_name, buf_namespace, &support, &node_ops);
rclc_node_init_default(&nodes[i], buf_name, buf_namespace, &support);
}

// create publishers
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,11 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create nodes
for(size_t i = 0; i < ENTITY_NUMBER; i++){
Expand All @@ -41,9 +45,7 @@ void microros_app(void)
snprintf(buf_namespace, 100, "ns_%d", i);

// create node
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&nodes[i], buf_name, buf_namespace, &support, &node_ops);
rclc_node_init_default(&nodes[i], buf_name, buf_namespace, &support);
}

// create publishers
Expand Down Expand Up @@ -95,6 +97,6 @@ void microros_app(void)
{
rcl_publisher_fini(&publishers[i], &nodes[i]);
rcl_subscription_fini(&subscribers[i], &nodes[i]);
rcl_node_fini(&nodes[i]);
rcl_node_fini(&nodes[i]);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,15 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create nodes
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publishers
rcl_publisher_t publishers[ENTITY_NUMBER];
Expand Down
16 changes: 9 additions & 7 deletions test/micro_ros_renesas_testbench/client_tests/Parameters.c
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,17 @@ void microros_app(void)

//create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create nodes
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// Create parameter service
// create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// Create parameter service
rclc_parameter_server_t param_server;
rclc_parameter_server_init_default(&param_server, &node);

Expand Down
16 changes: 9 additions & 7 deletions test/micro_ros_renesas_testbench/client_tests/Ping.c
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,17 @@ void microros_app(void)
// micro-ROS app
rcl_allocator_t allocator = rcl_get_default_allocator();

// create init_options
// Create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node_ping", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// Create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node_ping", "", &support);

// create publisher
rcl_publisher_t publisher;
Expand Down
16 changes: 9 additions & 7 deletions test/micro_ros_renesas_testbench/client_tests/Publisher.c
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,17 @@ void microros_app(void)
{
rcl_allocator_t allocator = rcl_get_default_allocator();

//create init_options
// Create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create nodes
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// Create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publisher
rcl_publisher_t publisher;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,17 @@ void microros_app(void)
{
rcl_allocator_t allocator = rcl_get_default_allocator();

// Create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create node
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// Create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "char_long_sequence_publisher_rcl", "", &support, &node_ops);
rclc_node_init_default(&node, "char_long_sequence_publisher_rcl", "", &support);

// create publisher
rcl_publisher_t publisher;
Expand Down
16 changes: 9 additions & 7 deletions test/micro_ros_renesas_testbench/client_tests/PublisherRate.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,17 @@ void microros_app(void)
// micro-ROS app
rcl_allocator_t allocator = rcl_get_default_allocator();

// create init_options
// Create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

// create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// Create node
rcl_node_t node;
rclc_node_init_default(&node, "test_node", "", &support);

// create publisher
rclc_publisher_init_best_effort(
Expand Down
11 changes: 7 additions & 4 deletions test/micro_ros_renesas_testbench/client_tests/RTT.c
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,17 @@ void microros_app(void)
{
rcl_allocator_t allocator = rcl_get_default_allocator();

// Create init_options
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &allocator);

rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
rcl_init_options_init(&init_options, allocator);
rcl_init_options_set_domain_id(&init_options, DOMAIN_ID);
rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator);

// Create node
rcl_node_t node;
rcl_node_options_t node_ops = rcl_node_get_default_options();
node_ops.domain_id = (size_t)(DOMAIN_ID);
rclc_node_init_with_options(&node, "test_node", "", &support, &node_ops);
rclc_node_init_default(&node, "test_node", "", &support);

// Create publisher
rclc_publisher_init_default(
Expand Down
Loading