Aikido
RosPositionCommandExecutor.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
3 
4 #include <chrono>
5 #include <future>
6 #include <mutex>
7 
8 #include <Eigen/Dense>
9 #include <actionlib/client/action_client.h>
10 #include <pr_control_msgs/SetPositionAction.h>
11 #include <ros/callback_queue.h>
12 #include <ros/ros.h>
13 #include <sensor_msgs/JointState.h>
14 
16 
17 namespace aikido {
18 namespace control {
19 namespace ros {
20 
26 {
27 public:
35  ::ros::NodeHandle node,
36  const std::string& serverName,
37  std::vector<std::string> jointNames,
38  std::chrono::milliseconds connectionTimeout
39  = std::chrono::milliseconds{1000},
40  std::chrono::milliseconds connectionPollingPeriod
41  = std::chrono::milliseconds{20});
42 
44 
47  std::future<void> execute(const Eigen::VectorXd& goalPositions) override;
48 
53  void step(const std::chrono::system_clock::time_point& timepoint) override;
54 
55 private:
57  = actionlib::ActionClient<pr_control_msgs::SetPositionAction>;
58  using GoalHandle = RosPositionActionClient::GoalHandle;
59 
60  void transitionCallback(GoalHandle handle);
61 
62  ::ros::NodeHandle mNode;
63  ::ros::CallbackQueue mCallbackQueue;
65  RosPositionActionClient::GoalHandle mGoalHandle;
66 
67  std::vector<std::string> mJointNames;
68 
69  std::chrono::milliseconds mConnectionTimeout;
70  std::chrono::milliseconds mConnectionPollingPeriod;
71 
73  std::unique_ptr<std::promise<void>> mPromise;
74 
76  mutable std::mutex mMutex;
77 };
78 
79 } // namespace ros
80 } // namespace control
81 } // namespace aikido
82 
83 #endif // ifndef AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
aikido::control::ros::RosPositionCommandExecutor::transitionCallback
void transitionCallback(GoalHandle handle)
aikido::control::ros::RosPositionCommandExecutor::execute
std::future< void > execute(const Eigen::VectorXd &goalPositions) override
Sends positions to ROS server for execution.
aikido::control::ros::RosPositionCommandExecutor::mJointNames
std::vector< std::string > mJointNames
Definition: RosPositionCommandExecutor.hpp:67
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::control::ros::RosPositionCommandExecutor::mGoalHandle
RosPositionActionClient::GoalHandle mGoalHandle
Definition: RosPositionCommandExecutor.hpp:65
aikido::control::ros::RosPositionCommandExecutor::mMutex
std::mutex mMutex
Manages access to mInProgress, mPromise.
Definition: RosPositionCommandExecutor.hpp:76
aikido::control::ros::RosPositionCommandExecutor::mInProgress
bool mInProgress
Definition: RosPositionCommandExecutor.hpp:72
aikido::control::ros::RosPositionCommandExecutor::RosPositionCommandExecutor
RosPositionCommandExecutor(::ros::NodeHandle node, const std::string &serverName, std::vector< std::string > jointNames, std::chrono::milliseconds connectionTimeout=std::chrono::milliseconds{1000}, std::chrono::milliseconds connectionPollingPeriod=std::chrono::milliseconds{20})
Constructor.
aikido::control::ros::RosPositionCommandExecutor::step
void step(const std::chrono::system_clock::time_point &timepoint) override
Step to a point in time.
aikido::control::ros::RosPositionCommandExecutor::~RosPositionCommandExecutor
virtual ~RosPositionCommandExecutor()
aikido::control::PositionCommandExecutor
Abstract class for executing position commands.
Definition: PositionCommandExecutor.hpp:23
aikido::control::ros::RosPositionCommandExecutor
This class uses actionlib to command an action of the type pr_control_msgs/SetPosition.
Definition: RosPositionCommandExecutor.hpp:24
aikido::control::ros::RosPositionCommandExecutor::mPromise
std::unique_ptr< std::promise< void > > mPromise
Definition: RosPositionCommandExecutor.hpp:73
aikido::control::ros::RosPositionCommandExecutor::mConnectionPollingPeriod
std::chrono::milliseconds mConnectionPollingPeriod
Definition: RosPositionCommandExecutor.hpp:70
aikido::control::ros::RosPositionCommandExecutor::mNode
::ros::NodeHandle mNode
Definition: RosPositionCommandExecutor.hpp:62
aikido::control::ros::RosPositionCommandExecutor::GoalHandle
RosPositionActionClient::GoalHandle GoalHandle
Definition: RosPositionCommandExecutor.hpp:58
aikido::control::ros::RosPositionCommandExecutor::RosPositionActionClient
actionlib::ActionClient< pr_control_msgs::SetPositionAction > RosPositionActionClient
Definition: RosPositionCommandExecutor.hpp:57
PositionCommandExecutor.hpp
aikido::control::ros::RosPositionCommandExecutor::mCallbackQueue
::ros::CallbackQueue mCallbackQueue
Definition: RosPositionCommandExecutor.hpp:63
aikido::control::ros::RosPositionCommandExecutor::mClient
RosPositionActionClient mClient
Definition: RosPositionCommandExecutor.hpp:64
aikido::control::ros::RosPositionCommandExecutor::mConnectionTimeout
std::chrono::milliseconds mConnectionTimeout
Definition: RosPositionCommandExecutor.hpp:69