segmentation fault for NULL dereference (#202)

* 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>
This commit is contained in:
Ethan Gao 2017-12-14 00:31:18 +08:00 committed by Karsten Knese
parent b41d4e333e
commit 261a46772f
2 changed files with 10 additions and 0 deletions

View file

@ -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);
@ -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);