Skip to content

Commit

Permalink
segmentation fault for NULL dereference (#202)
Browse files Browse the repository at this point in the history
* Invalid memory access for NULL dereference

rcl_lifecycle_get_state may return NULL

transition->goal is checked for NULL but no return
while it's true and this may result the follow-up
NULL dereference

Signed-off-by: Ethan Gao <ethan.gao@linux.intel.com>

* Avoid crash while NULL returned from rcl_service_get_options()

Signed-off-by: Ethan Gao <ethan.gao@linux.intel.com>

* tweak error string and null check for current_state

Signed-off-by: Ethan Gao <ethan.gao@linux.intel.com>
  • Loading branch information
gaoethan authored and Karsten1987 committed Dec 13, 2017
1 parent b41d4e3 commit 261a467
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 0 deletions.
4 changes: 4 additions & 0 deletions rcl/src/rcl/service.c
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,8 @@ rcl_take_request(
{
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Service server taking service request")
const rcl_service_options_t * options = rcl_service_get_options(service);
RCL_CHECK_FOR_NULL_WITH_MSG(
options, "Failed to get service options", return RCL_RET_ERROR, rcl_get_default_allocator());
RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT, options->allocator);
RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT, options->allocator);

Expand All @@ -273,6 +275,8 @@ rcl_send_response(
{
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Sending service response")
const rcl_service_options_t * options = rcl_service_get_options(service);
RCL_CHECK_FOR_NULL_WITH_MSG(
options, "Failed to get service options", return RCL_RET_ERROR, rcl_get_default_allocator());
RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT, options->allocator);
RCL_CHECK_ARGUMENT_FOR_NULL(ros_response, RCL_RET_INVALID_ARGUMENT, options->allocator);

Expand Down
6 changes: 6 additions & 0 deletions rcl_lifecycle/src/rcl_lifecycle.c
Original file line number Diff line number Diff line change
Expand Up @@ -285,15 +285,20 @@ rcl_lifecycle_is_valid_transition(
const rcl_lifecycle_state_t * current_state = rcl_lifecycle_get_state(
&state_machine->transition_map, current_id);

RCL_CHECK_FOR_NULL_WITH_MSG(current_state,
"rcl_lifecycle_get_state returns NULL", return NULL, rcl_get_default_allocator());

for (unsigned int i = 0; i < current_state->valid_transition_size; ++i) {
if (current_state->valid_transition_keys[i] == key) {
return &current_state->valid_transitions[i];
}
}

RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"No callback transition matching %d found for current state %s",
key, state_machine->current_state->label)

return NULL;
}

Expand All @@ -318,6 +323,7 @@ rcl_lifecycle_trigger_transition(
if (!transition->goal) {
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "No valid goal is set")
return RCL_RET_ERROR;
}
state_machine->current_state = transition->goal;
if (publish_notification) {
Expand Down

0 comments on commit 261a467

Please sign in to comment.