-
Notifications
You must be signed in to change notification settings - Fork 435
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
rclcpp_action Server implementation #593
Conversation
784edbd
to
6747d0a
Compare
7583828
to
ca19322
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Partial review. Just some minor comments, LGTM!
rclcpp_action/src/server.cpp
Outdated
{ | ||
if (nullptr != ptr) { | ||
rcl_ret_t fail_ret = rcl_action_goal_handle_fini(ptr); | ||
(void)fail_ret; // TODO(sloretz) do something with error during cleanup |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Logging an error message seems like the only thing to do here.
} | ||
|
||
void | ||
ServerBase::publish_status() |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Just a thought:
IIRC, there was discussion in the design doc about making the status (and feedback) publisher optional. I'm not sure if we had any ideas about how the implementation would look, but given time constraints it's probably good to capture this feature in a ticket to tackle at a later time.
It might make sense to instead have the option to disable subscribers in the action client so then CLI tools can always interact with action servers.
ServerBase::publish_result(const std::array<uint8_t, 16> & uuid, std::shared_ptr<void> result_msg) | ||
{ | ||
// Check that the goal exists | ||
rcl_action_goal_info_t goal_info; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Since the uuid -> goal_info
conversion is happening in several places, it would be nice to wrap in a utility function. Perhaps after we have the GoalID wrapper introduced by #594
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
One observation: we use GoalID
everywhere, but the other fields of GoalInfo
are in many places meaningless.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Added conversion function in f717e9b
rclcpp_action/test/test_server.cpp
Outdated
|
||
using GoalHandle = rclcpp_action::ServerGoalHandle<test_msgs::action::Fibonacci>; | ||
auto as = rclcpp_action::create_server<test_msgs::action::Fibonacci>(node.get(), "fibonacci", | ||
[](rcl_action_goal_info_t &, test_msgs::action::Fibonacci::Goal *) {}, | ||
auto as = rclcpp_action::create_server<test_msgs::action::Fibonacci>(node, "fibonacci", |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We could add tests for invalid constructions (e.g. invalid node or action name).
70ccd21
to
63eff6c
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Leaving some comments, awesome work @sloretz !
{ | ||
std::lock_guard<std::mutex> lock(goal_handles_mutex_); | ||
CancelResponse resp = CancelResponse::REJECT; | ||
std::shared_ptr<rcl_action_goal_handle_t> rcl_handle; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz unused?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Removed in 03c9cf0
} | ||
|
||
/// Get the unique identifier of the goal | ||
const GoalID |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz why not const GoalID &
instead?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Constant reference returned in ea33c88
rclcpp_action/src/server.cpp
Outdated
(void)node_base; | ||
(void)name; | ||
(void)type_support; | ||
rcl_ret_t ret; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz consider not declaring ret
until you can assign something to it (e.g. line 91 below).
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Moved below in 8a21dec
rclcpp_action/src/server.cpp
Outdated
|
||
return pimpl_->goal_request_ready_ || | ||
pimpl_->cancel_request_ready_ || | ||
pimpl_->result_request_ready_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz looks like pimpl_->goal_expired_
is missing.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Whoops, added in bf4797a
void | ||
ServerBase::execute_goal_request_received() | ||
{ | ||
rcl_ret_t ret; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz same suggestion about scoping ret
stream << static_cast<int>(element); | ||
} | ||
return stream.str(); | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
+100
rclcpp_action/test/test_server.cpp
Outdated
|
||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>; | ||
auto as = rclcpp_action::create_server<Fibonacci>(node, "fibonacci", | ||
[](const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz consider using GoalID
instead of std::array<...>
.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
GoalID in 71c7100
rclcpp_action/test/test_server.cpp
Outdated
|
||
auto request = std::make_shared<Fibonacci::GoalRequestService::Request>(); | ||
|
||
const std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@sloretz consider making this a constant member field in the fixture class.
* Three callbacks must be provided: | ||
* - one to accept or reject goals sent to the server, | ||
* - one to accept or reject requests to cancel a goal, | ||
* - one to given a goal handle after a goal has been accepted. |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Not sure I understand what the third bullet means.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reworded in de1510b
GoalID uuid, std::shared_ptr<void> goal_request_message) override | ||
{ | ||
std::shared_ptr<ServerGoalHandle<ActionT>> goal_handle; | ||
std::weak_ptr<Server<ActionT>> weak_this = this->shared_from_this(); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Hmm, so neither the server gets a hold of the goal handle, nor the handle gets a hold of the server. Is that right?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Yeah, this is making sure the server or server goal handle can be safely destructed in either order.
{ | ||
std::lock_guard<std::mutex> lock(rcl_handle_mutex_); | ||
// Check if the goal reached a terminal state already | ||
const bool active = rcl_action_goal_handle_is_active(rcl_handle_.get()); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We can use a short-cut and check if the goal is cancelable:
const bool is_cancelable = rcl_action_goal_handle_is_cancelable(rcl_handle.get());
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
What's the short cut? IIUC it looks like the code below would be the same.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
If the goal can be transitioned to canceling, then we don't need to get the state at L124 and check if the state is GOAL_STATE_CANCELING
at L130. But in the case is_cancelable
is false, then we still need to check I guess.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think this is equivalent to the current implementation:
const bool is_cancelable = rcl_action_goal_handle_is_cancelable(rcl_handle_.get());
if (is_cancelable) {
ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCEL);
if (RCL_RET_OK != ret) {
return false;
}
}
// Get the state
ret = rcl_action_goal_handle_get_status(rcl_handle_.get(), &state);
if (RCL_RET_OK != ret) {
return false;
}
// If it's canceling, cancel it
if (GOAL_STATE_CANCELING == state) {
ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_SET_CANCELED);
return RCL_RET_OK == ret;
}
return false;
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Mind making a follow up PR with this?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
LGTM
* Commiting to back up work, does not function * Can call user callback when goal request received * fini action server in destructor * rename user callback virtual functions * handle_execute test passes * Remove out of date comment * Refactor execute into three functions * Remove unused file * Add failing cancel test * Cancel test passes * Remove out of date comments * Make sure server publishes status when accepting a goal * Send status when goals transition to cancelling * Refactored sending goal request to its own function * Refactor cancel request into it's own function * Comment with remaining tests * Executing and terminal state statuses * publish feedback works * server sends result to clients that request it * Remove out of date comment * Add ServerGoalHandle::is_active() * Cleanup when goals expire * Can pass in action server options * cpplint and uncrustify fixes * Fix clang warnings * Copy rcl goal handle * Fix clang warning * Use intermediate value to avoid left shift on 32bit integer * RCLCPP_ACTION_PUBLIC everwhere * Change callback parameter from C type to C++ * Add accessors for request and uuid * Feedback must include goal id * Document Server<> and ServerBase<> * handle_execute -> handle_accepted * Test deferred execution * only publish feedback if goal is executing * Documentation for ServerGoalHandle * document msg parameters * remove unnecessary fini * notify_goal_done only takes server * Use unique_indentifier_msgs * create_server accepts group and removes waitable * uncrustify * Use weak ptr to avoid crash if goal handle lives longer than server * Handle goal callback const message * Goal handle doesn't have server pointer anymore * Lock goal_handles_ on Server<> * rcl_action_server_t protected with mutex * ServerBase results protected with mutex * protect rcl goal handle with mutex * is_cancel_request -> is_canceling * Add missing include * use GoalID and change uuid -> goal_id * Keep rcl goal handle alive until it expires on server * uncrustify * Move UUID hash * Log messages in server * ACTION -> ActionT * Cancel abandoned goal handles * Add convert() for C and C++ goal id * Remove unused variable * Constant reference * Move variable declaration down * is_ready if goal expired * map[] default constructs if it doesn't exist * Use rcl_action_get_goal_status_array() * Array -> GoalID * Use reentrant mutex for everything * comment * scope exit to fini cancel response * using GoalID
Signed-off-by: Dan Rose <[email protected]>
…bject (ros2#593) Signed-off-by: Josh Langsfeld <[email protected]>
The example server in PR ros2/examples#216 has been updated to work with this PR https://github.com/ros2/examples/blob/75e3f7d4c1d4f26853fe5c894d3940e7cd7af1b1/rclcpp/minimal_action_server/not_composable.cpp
This PR requires #594 in a convoluted way: checkout that branch and merge this one into it.
requires ros2/rcl#343