Skip to content

Commit

Permalink
Address PR comments and fix test
Browse files Browse the repository at this point in the history
Signed-off-by: Mauro Passerino <[email protected]>
  • Loading branch information
Mauro Passerino committed Sep 18, 2024
1 parent eb57f71 commit 13a27f6
Show file tree
Hide file tree
Showing 5 changed files with 262 additions and 254 deletions.
12 changes: 4 additions & 8 deletions rclcpp_action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,16 +79,12 @@ if(BUILD_TESTING)

add_subdirectory(test/benchmark)

ament_add_gtest(test_ros2_actions test/test_actions.cpp TIMEOUT 180)
ament_add_test_label(test_ros2_actions mimick)
if(TARGET test_ros2_actions)
target_link_libraries(test_ros2_actions
ament_add_gtest(test_actions test/test_actions.cpp TIMEOUT 180)
ament_add_test_label(test_actions)
if(TARGET test_actions)
target_link_libraries(test_actions
${PROJECT_NAME}
mimick
rcl::rcl
rcl_action::rcl_action
rclcpp::rclcpp
rcutils::rcutils
${test_msgs_TARGETS}
)
endif()
Expand Down
9 changes: 4 additions & 5 deletions rclcpp_action/src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,6 +352,10 @@ ClientBase::is_ready(const rcl_wait_set_t & wait_set)
}

pimpl_->next_ready_event = std::numeric_limits<size_t>::max();
if (is_status_ready) {
pimpl_->next_ready_event = static_cast<size_t>(EntityType::StatusSubscription);
return true;
}

if (is_goal_response_ready) {
pimpl_->next_ready_event = static_cast<size_t>(EntityType::GoalClient);
Expand All @@ -373,11 +377,6 @@ ClientBase::is_ready(const rcl_wait_set_t & wait_set)
return true;
}

if (is_status_ready) {
pimpl_->next_ready_event = static_cast<size_t>(EntityType::StatusSubscription);
return true;
}

return false;
}

Expand Down
Loading

0 comments on commit 13a27f6

Please sign in to comment.