Aikido
|
This class uses actionlib to command an action of the type pr_control_msgs/JointGroupCommandAction. More...
#include <aikido/control/ros/RosJointGroupCommandClient.hpp>
Public Member Functions | |
RosJointGroupCommandClient (const ::ros::NodeHandle &node, const std::string &serverName, const std::vector< std::string > jointNames, const std::chrono::milliseconds connectionTimeout=std::chrono::milliseconds{1000}, const std::chrono::milliseconds connectionPollingPeriod=std::chrono::milliseconds{20}) | |
Constructor. More... | |
virtual | ~RosJointGroupCommandClient () |
std::future< int > | execute (ExecutorType type, const std::vector< double > &goal, ::ros::Duration timeout) |
Send command to ROS server for execution. More... | |
void | step () |
Step to a point in time. More... | |
void | cancel () |
Cancel current command. More... | |
Private Types | |
using | JointGroupCommandActionClient = actionlib::ActionClient< pr_control_msgs::JointGroupCommandAction > |
using | GoalHandle = JointGroupCommandActionClient::GoalHandle |
Private Member Functions | |
void | transitionCallback (GoalHandle handle) |
Private Attributes | |
const ::ros::NodeHandle | mNode |
::ros::CallbackQueue | mCallbackQueue |
JointGroupCommandActionClient | mClient |
JointGroupCommandActionClient::GoalHandle | mGoalHandle |
std::vector< std::string > | mJointNames |
std::chrono::milliseconds | mConnectionTimeout |
std::chrono::milliseconds | mConnectionPollingPeriod |
bool | mInProgress |
std::unique_ptr< std::promise< int > > | mPromise |
std::mutex | mMutex |
Manages access to mInProgress, mPromise. More... | |
This class uses actionlib to command an action of the type pr_control_msgs/JointGroupCommandAction.
It specifies a set of target command and sends it to the ROS server for execution
|
private |
|
private |
aikido::control::ros::RosJointGroupCommandClient::RosJointGroupCommandClient | ( | const ::ros::NodeHandle & | node, |
const std::string & | serverName, | ||
const std::vector< std::string > | jointNames, | ||
const std::chrono::milliseconds | connectionTimeout = std::chrono::milliseconds{1000} , |
||
const std::chrono::milliseconds | connectionPollingPeriod = std::chrono::milliseconds{20} |
||
) |
Constructor.
[in] | node | ROS node handle for action client. |
[in] | serverName | Name of the server to send trajectory to. |
[in] | jointNames | The names of the joints to set position targets for |
[in] | connectionTimeout | Timeout for server connection. |
[in] | connectionPollingPeriod | Polling period for server connection. |
|
virtual |
void aikido::control::ros::RosJointGroupCommandClient::cancel | ( | ) |
Cancel current command.
Should trigger exception for active std::promise
std::future<int> aikido::control::ros::RosJointGroupCommandClient::execute | ( | ExecutorType | type, |
const std::vector< double > & | goal, | ||
::ros::Duration | timeout | ||
) |
Send command to ROS server for execution.
[in] | type | Selecting between Position, Velocity, or Effort |
[in] | goal | Vector of target positions for each joint |
[in] | timeout | How long until command should expire |
void aikido::control::ros::RosJointGroupCommandClient::step | ( | ) |
Step to a point in time.
timepoint
can be a time in the future to enable faster than real-time execution.timepoint | Time to simulate to To be executed on a separate thread. Regularly checks for the completion of a sent command. |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
mutableprivate |
Manages access to mInProgress, mPromise.
|
private |
|
private |