-
Notifications
You must be signed in to change notification settings - Fork 30
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
Cancel in-progress trajectories. #400
Changes from 5 commits
df30f1c
bba5d44
4ff1bf4
d18d869
2ff827e
0805f10
8b5e378
28a7221
1d1b281
2b43da7
9e360d2
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -234,7 +234,11 @@ void RosTrajectoryExecutor::step( | |
//============================================================================== | ||
void RosTrajectoryExecutor::abort() | ||
{ | ||
// TODO: cancel the actionlib goal (once there is support in ReWD controller) | ||
std::lock_guard<std::mutex> lock(mMutex); | ||
DART_UNUSED(lock); // Suppress unused variable warning. | ||
|
||
if (mInProgress) | ||
mGoalHandle.cancel(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Would it be useful to print a warning something like "Attempting to abort trajectory execution but no trajectory in progress."? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. That sounds like a good idea. We should do this to the other |
||
} | ||
|
||
} // namespace ros | ||
|
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'd prefer "cancel" instead of "abort". It seems like "cancel" and "abort" are different terms in ros_control; "cancel" is where the client requested to cancel the trajectory, and "abort" is where the server had to stop it for some other reason (e.g. force threshold has been violated).
http://wiki.ros.org/actionlib/DetailedDescription