Go to the documentation of this file. 1 #ifndef AIKIDO_CONTROL_ROS_ROSJOINTGROUPCOMMANDCLIENT_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSJOINTGROUPCOMMANDCLIENT_HPP_
8 #include <actionlib/client/action_client.h>
9 #include <pr_control_msgs/JointGroupCommandAction.h>
10 #include <ros/callback_queue.h>
32 const ::ros::NodeHandle& node,
33 const std::string& serverName,
34 const std::vector<std::string> jointNames,
35 const std::chrono::milliseconds connectionTimeout
36 = std::chrono::milliseconds{1000},
37 const std::chrono::milliseconds connectionPollingPeriod
38 = std::chrono::milliseconds{20});
48 const std::vector<double>& goal,
49 ::ros::Duration timeout);
62 = actionlib::ActionClient<pr_control_msgs::JointGroupCommandAction>;
63 using GoalHandle = JointGroupCommandActionClient::GoalHandle;
88 #endif // ifndef AIKIDO_CONTROL_ROS_ROSJOINTGROUPCOMMANDCLIENT_HPP_
std::chrono::milliseconds mConnectionTimeout
Definition: RosJointGroupCommandClient.hpp:74
void transitionCallback(GoalHandle handle)
std::unique_ptr< std::promise< int > > mPromise
Definition: RosJointGroupCommandClient.hpp:78
const ::ros::NodeHandle mNode
Definition: RosJointGroupCommandClient.hpp:67
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
This class uses actionlib to command an action of the type pr_control_msgs/JointGroupCommandAction.
Definition: RosJointGroupCommandClient.hpp:22
JointGroupCommandActionClient mClient
Definition: RosJointGroupCommandClient.hpp:69
std::chrono::milliseconds mConnectionPollingPeriod
Definition: RosJointGroupCommandClient.hpp:75
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.
void cancel()
Cancel current command.
std::mutex mMutex
Manages access to mInProgress, mPromise.
Definition: RosJointGroupCommandClient.hpp:81
std::vector< std::string > mJointNames
Definition: RosJointGroupCommandClient.hpp:72
JointGroupCommandActionClient::GoalHandle GoalHandle
Definition: RosJointGroupCommandClient.hpp:63
::ros::CallbackQueue mCallbackQueue
Definition: RosJointGroupCommandClient.hpp:68
JointGroupCommandActionClient::GoalHandle mGoalHandle
Definition: RosJointGroupCommandClient.hpp:70
ExecutorType
Type of executor Can be used to determine if 2 executors make conflicting demands of individual degre...
Definition: Executor.hpp:35
std::future< int > execute(ExecutorType type, const std::vector< double > &goal, ::ros::Duration timeout)
Send command to ROS server for execution.
bool mInProgress
Definition: RosJointGroupCommandClient.hpp:77
void step()
Step to a point in time.
actionlib::ActionClient< pr_control_msgs::JointGroupCommandAction > JointGroupCommandActionClient
Definition: RosJointGroupCommandClient.hpp:62
virtual ~RosJointGroupCommandClient()