Add macro semicolons (#303)
* Add semicolons to all RCLCPP and RCUTILS macros. Signed-off-by: Chris Lalancette <clalancette@openrobotics.org> * Add semicolons in Windows stdatomic_helper.h Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
This commit is contained in:
parent
f1293b7d3b
commit
3d0e2b7966
17 changed files with 125 additions and 124 deletions
|
@ -145,20 +145,20 @@ rcl_lifecycle_com_interface_init(
|
|||
|
||||
fail:
|
||||
if (RCL_RET_OK != rcl_publisher_fini(&com_interface->pub_transition_event, node_handle)) {
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy transition_event publisher")
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy transition_event publisher");
|
||||
}
|
||||
if (RCL_RET_OK != rcl_service_fini(&com_interface->srv_change_state, node_handle)) {
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy change_state service")
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy change_state service");
|
||||
}
|
||||
if (RCL_RET_OK != rcl_service_fini(&com_interface->srv_get_state, node_handle)) {
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy get_state service")
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy get_state service");
|
||||
}
|
||||
if (RCL_RET_OK != rcl_service_fini(&com_interface->srv_get_available_states, node_handle)) {
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy get_available_states service")
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to destroy get_available_states service");
|
||||
}
|
||||
if (RCL_RET_OK != rcl_service_fini(&com_interface->srv_get_available_transitions, node_handle)) {
|
||||
RCUTILS_LOG_ERROR_NAMED(
|
||||
ROS_PACKAGE_NAME, "Failed to destroy get_available_transitions service")
|
||||
ROS_PACKAGE_NAME, "Failed to destroy get_available_transitions service");
|
||||
}
|
||||
|
||||
return RCL_RET_ERROR;
|
||||
|
|
|
@ -297,7 +297,7 @@ rcl_lifecycle_is_valid_transition(
|
|||
RCUTILS_LOG_WARN_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"No callback transition matching %d found for current state %s",
|
||||
key, state_machine->current_state->label)
|
||||
key, state_machine->current_state->label);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
@ -315,14 +315,14 @@ rcl_lifecycle_trigger_transition(
|
|||
RCUTILS_LOG_ERROR_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"No transition found for node %s with key %d",
|
||||
state_machine->current_state->label, key)
|
||||
state_machine->current_state->label, key);
|
||||
RCL_SET_ERROR_MSG("Transition is not registered.", rcl_get_default_allocator());
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
|
||||
if (!transition->goal) {
|
||||
RCUTILS_LOG_ERROR_NAMED(
|
||||
ROS_PACKAGE_NAME, "No valid goal is set")
|
||||
ROS_PACKAGE_NAME, "No valid goal is set");
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
state_machine->current_state = transition->goal;
|
||||
|
@ -349,14 +349,14 @@ rcl_print_state_machine(const rcl_lifecycle_state_machine_t * state_machine)
|
|||
"Primary State: %s(%u)\n# of valid transitions: %u",
|
||||
map->states[i].label, map->states[i].id,
|
||||
map->states[i].valid_transition_size
|
||||
)
|
||||
);
|
||||
for (size_t j = 0; j < map->states[i].valid_transition_size; ++j) {
|
||||
RCUTILS_LOG_INFO_NAMED(
|
||||
ROS_PACKAGE_NAME,
|
||||
"\tNode %s: Key %d: Transition: %s",
|
||||
map->states[i].label,
|
||||
map->states[i].valid_transition_keys[j],
|
||||
map->states[i].valid_transitions[j].label)
|
||||
map->states[i].valid_transitions[j].label);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -229,7 +229,7 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
|
|||
*it == lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE ||
|
||||
*it == lifecycle_msgs__msg__Transition__TRANSITION_SHUTDOWN) {continue;}
|
||||
|
||||
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "applying key %u", *it)
|
||||
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "applying key %u", *it);
|
||||
EXPECT_EQ(
|
||||
RCL_RET_ERROR, rcl_lifecycle_trigger_transition(&state_machine, *it, false));
|
||||
rcl_reset_error();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue