Aikido
RosJointGroupCommandClient.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONTROL_ROS_ROSJOINTGROUPCOMMANDCLIENT_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSJOINTGROUPCOMMANDCLIENT_HPP_
3 
4 #include <chrono>
5 #include <future>
6 #include <mutex>
7 
8 #include <actionlib/client/action_client.h>
9 #include <pr_control_msgs/JointGroupCommandAction.h>
10 #include <ros/callback_queue.h>
11 #include <ros/ros.h>
12 
14 
15 namespace aikido {
16 namespace control {
17 namespace ros {
18 
23 {
24 public:
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});
39 
41 
46  std::future<int> execute(
47  ExecutorType type,
48  const std::vector<double>& goal,
49  ::ros::Duration timeout);
50 
54  void step();
55 
58  void cancel();
59 
60 private:
62  = actionlib::ActionClient<pr_control_msgs::JointGroupCommandAction>;
63  using GoalHandle = JointGroupCommandActionClient::GoalHandle;
64 
65  void transitionCallback(GoalHandle handle);
66 
67  const ::ros::NodeHandle mNode;
68  ::ros::CallbackQueue mCallbackQueue;
70  JointGroupCommandActionClient::GoalHandle mGoalHandle;
71 
72  std::vector<std::string> mJointNames;
73 
74  std::chrono::milliseconds mConnectionTimeout;
75  std::chrono::milliseconds mConnectionPollingPeriod;
76 
78  std::unique_ptr<std::promise<int>> mPromise;
79 
81  mutable std::mutex mMutex;
82 };
83 
84 } // namespace ros
85 } // namespace control
86 } // namespace aikido
87 
88 #endif // ifndef AIKIDO_CONTROL_ROS_ROSJOINTGROUPCOMMANDCLIENT_HPP_
aikido::control::ros::RosJointGroupCommandClient::mConnectionTimeout
std::chrono::milliseconds mConnectionTimeout
Definition: RosJointGroupCommandClient.hpp:74
aikido::control::ros::RosJointGroupCommandClient::transitionCallback
void transitionCallback(GoalHandle handle)
aikido::control::ros::RosJointGroupCommandClient::mPromise
std::unique_ptr< std::promise< int > > mPromise
Definition: RosJointGroupCommandClient.hpp:78
aikido::control::ros::RosJointGroupCommandClient::mNode
const ::ros::NodeHandle mNode
Definition: RosJointGroupCommandClient.hpp:67
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::control::ros::RosJointGroupCommandClient
This class uses actionlib to command an action of the type pr_control_msgs/JointGroupCommandAction.
Definition: RosJointGroupCommandClient.hpp:22
aikido::control::ros::RosJointGroupCommandClient::mClient
JointGroupCommandActionClient mClient
Definition: RosJointGroupCommandClient.hpp:69
aikido::control::ros::RosJointGroupCommandClient::mConnectionPollingPeriod
std::chrono::milliseconds mConnectionPollingPeriod
Definition: RosJointGroupCommandClient.hpp:75
aikido::control::ros::RosJointGroupCommandClient::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.
aikido::control::ros::RosJointGroupCommandClient::cancel
void cancel()
Cancel current command.
aikido::control::ros::RosJointGroupCommandClient::mMutex
std::mutex mMutex
Manages access to mInProgress, mPromise.
Definition: RosJointGroupCommandClient.hpp:81
aikido::control::ros::RosJointGroupCommandClient::mJointNames
std::vector< std::string > mJointNames
Definition: RosJointGroupCommandClient.hpp:72
aikido::control::ros::RosJointGroupCommandClient::GoalHandle
JointGroupCommandActionClient::GoalHandle GoalHandle
Definition: RosJointGroupCommandClient.hpp:63
Executor.hpp
aikido::control::ros::RosJointGroupCommandClient::mCallbackQueue
::ros::CallbackQueue mCallbackQueue
Definition: RosJointGroupCommandClient.hpp:68
aikido::control::ros::RosJointGroupCommandClient::mGoalHandle
JointGroupCommandActionClient::GoalHandle mGoalHandle
Definition: RosJointGroupCommandClient.hpp:70
aikido::control::ExecutorType
ExecutorType
Type of executor Can be used to determine if 2 executors make conflicting demands of individual degre...
Definition: Executor.hpp:35
aikido::control::ros::RosJointGroupCommandClient::execute
std::future< int > execute(ExecutorType type, const std::vector< double > &goal, ::ros::Duration timeout)
Send command to ROS server for execution.
aikido::control::ros::RosJointGroupCommandClient::mInProgress
bool mInProgress
Definition: RosJointGroupCommandClient.hpp:77
aikido::control::ros::RosJointGroupCommandClient::step
void step()
Step to a point in time.
aikido::control::ros::RosJointGroupCommandClient::JointGroupCommandActionClient
actionlib::ActionClient< pr_control_msgs::JointGroupCommandAction > JointGroupCommandActionClient
Definition: RosJointGroupCommandClient.hpp:62
aikido::control::ros::RosJointGroupCommandClient::~RosJointGroupCommandClient
virtual ~RosJointGroupCommandClient()