move allocator and error handling to c utilities (#122)

* moved allocator to c_utilities

* moved error_handling to c_utilities

* refactor uses of RCL_SET_ERROR_MSG with allocator

* add missing guard condition functions and tests

* add missing timer functions

* refactor rcl_lifecycyle

* missed an instance of RCL_SET_ERROR_MSG

* fix segfaults in error cases for rcl_lifecycle

* remove extra header

* check return code of rcl_lifecycle_init_default_state_machine
This commit is contained in:
William Woodall 2017-04-19 12:37:48 -07:00 committed by GitHub
parent 415612f8af
commit 90176d9f1a
33 changed files with 872 additions and 618 deletions

View file

@ -84,6 +84,8 @@ typedef struct rcl_lifecycle_state_machine_t
rcl_lifecycle_transition_map_t transition_map;
// Communication interface into a ROS world
rcl_lifecycle_com_interface_t com_interface;
// Allocator used.
rcl_allocator_t allocator;
} rcl_lifecycle_state_machine_t;
#if __cplusplus

View file

@ -67,24 +67,32 @@ rcl_lifecycle_com_interface_init(rcl_lifecycle_com_interface_t * com_interface,
const rosidl_service_type_support_t * ts_srv_get_available_states,
const rosidl_service_type_support_t * ts_srv_get_available_transitions)
{
if (!node_handle) {
RCL_SET_ERROR_MSG("node_handle is null", rcl_get_default_allocator());
return RCL_RET_INVALID_ARGUMENT;
}
const rcl_node_options_t * node_options = rcl_node_get_options(node_handle);
if (!node_options) {
return RCL_RET_NODE_INVALID;
}
if (!ts_pub_notify) {
RCL_SET_ERROR_MSG("ts_pub_notify is NULL");
RCL_SET_ERROR_MSG("ts_pub_notify is NULL", node_options->allocator);
return RCL_RET_ERROR;
}
if (!ts_srv_change_state) {
RCL_SET_ERROR_MSG("ts_srv_change_state is NULL");
RCL_SET_ERROR_MSG("ts_srv_change_state is NULL", node_options->allocator);
return RCL_RET_ERROR;
}
if (!ts_srv_get_state) {
RCL_SET_ERROR_MSG("ts_srv_get_state is NULL");
RCL_SET_ERROR_MSG("ts_srv_get_state is NULL", node_options->allocator);
return RCL_RET_ERROR;
}
if (!ts_srv_get_available_states) {
RCL_SET_ERROR_MSG("ts_srv_get_available_states is NULL");
RCL_SET_ERROR_MSG("ts_srv_get_available_states is NULL", node_options->allocator);
return RCL_RET_ERROR;
}
if (!ts_srv_get_available_states) {
RCL_SET_ERROR_MSG("ts_srv_get_available_transitions is NULL");
RCL_SET_ERROR_MSG("ts_srv_get_available_transitions is NULL", node_options->allocator);
return RCL_RET_ERROR;
}
@ -97,7 +105,7 @@ rcl_lifecycle_com_interface_init(rcl_lifecycle_com_interface_t * com_interface,
const char * topic_prefix = "__transition_event";
char * topic_name;
if (!concatenate(&node_name, &topic_prefix, &topic_name)) {
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255");
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255", node_options->allocator);
goto fail;
}
@ -122,7 +130,7 @@ rcl_lifecycle_com_interface_init(rcl_lifecycle_com_interface_t * com_interface,
const char * topic_prefix = "__change_state";
char * topic_name;
if (!concatenate(&node_name, &topic_prefix, &topic_name)) {
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255");
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255", node_options->allocator);
goto fail;
}
@ -144,7 +152,7 @@ rcl_lifecycle_com_interface_init(rcl_lifecycle_com_interface_t * com_interface,
const char * topic_prefix = "__get_state";
char * topic_name;
if (!concatenate(&node_name, &topic_prefix, &topic_name)) {
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255");
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255", node_options->allocator);
goto fail;
}
@ -166,7 +174,7 @@ rcl_lifecycle_com_interface_init(rcl_lifecycle_com_interface_t * com_interface,
const char * topic_prefix = "__get_available_states";
char * topic_name;
if (!concatenate(&node_name, &topic_prefix, &topic_name)) {
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255");
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255", node_options->allocator);
goto fail;
}
@ -188,7 +196,7 @@ rcl_lifecycle_com_interface_init(rcl_lifecycle_com_interface_t * com_interface,
const char * topic_prefix = "__get_available_transitions";
char * topic_name;
if (!concatenate(&node_name, &topic_prefix, &topic_name)) {
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255");
RCL_SET_ERROR_MSG("Topic name exceeds maximum size of 255", node_options->allocator);
goto fail;
}

View file

@ -41,6 +41,10 @@ rcl_lifecycle_get_zero_initialized_state_machine()
state_machine.transition_map.transitions = NULL;
state_machine.transition_map.transitions_size = 0;
state_machine.com_interface = rcl_lifecycle_get_zero_initialized_com_interface();
state_machine.allocator.allocate = NULL;
state_machine.allocator.deallocate = NULL;
state_machine.allocator.reallocate = NULL;
state_machine.allocator.state = NULL;
return state_machine;
}
@ -65,8 +69,19 @@ rcl_lifecycle_state_machine_init(
}
if (default_states) {
rcl_lifecycle_init_default_state_machine(state_machine);
rcl_ret_t ret = rcl_lifecycle_init_default_state_machine(state_machine);
if (ret != RCL_RET_OK) {
// error should already be set
return ret;
}
}
const rcl_node_options_t * node_options = rcl_node_get_options(node_handle);
if (!node_options) {
RCL_SET_ERROR_MSG("node does not have valid options", rcl_get_default_allocator());
return RCL_RET_NODE_INVALID;
}
state_machine->allocator = node_options->allocator;
return RCL_RET_OK;
}
@ -100,11 +115,11 @@ rcl_ret_t
rcl_lifecycle_state_machine_is_initialized(const rcl_lifecycle_state_machine_t * state_machine)
{
if (!state_machine->com_interface.srv_get_state.impl) {
RCL_SET_ERROR_MSG("get_state service is null");
RCL_SET_ERROR_MSG("get_state service is null", rcl_get_default_allocator());
return RCL_RET_ERROR;
}
if (!state_machine->com_interface.srv_change_state.impl) {
RCL_SET_ERROR_MSG("change_state service is null");
RCL_SET_ERROR_MSG("change_state service is null", rcl_get_default_allocator());
return RCL_RET_ERROR;
}
return RCL_RET_OK;
@ -141,7 +156,7 @@ rcl_lifecycle_trigger_transition(
if (!transition) {
fprintf(stderr, "No transition found for node %s with key %d\n",
state_machine->current_state->label, key);
RCL_SET_ERROR_MSG("Transition is not registered.");
RCL_SET_ERROR_MSG("Transition is not registered.", rcl_get_default_allocator());
return RCL_RET_ERROR;
}