Aikido
RosTrajectoryExecutor.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONTROL_ROS_ROSTRAJECTORYEXECUTOR_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSTRAJECTORYEXECUTOR_HPP_
3 
4 #include <chrono>
5 #include <future>
6 #include <mutex>
7 
8 #include <actionlib/client/action_client.h>
9 #include <control_msgs/FollowJointTrajectoryAction.h>
10 #include <ros/callback_queue.h>
11 #include <ros/ros.h>
12 
15 
16 namespace aikido {
17 namespace control {
18 namespace ros {
19 
22 {
23 public:
32  ::ros::NodeHandle node,
33  const std::string& serverName,
34  double waypointTimestep,
35  double goalTimeTolerance,
36  const std::chrono::milliseconds& connectionTimeout
37  = std::chrono::milliseconds{1000},
38  const std::chrono::milliseconds& connectionPollingPeriod
39  = std::chrono::milliseconds{20});
40 
41  virtual ~RosTrajectoryExecutor();
42 
43  // Documentation inherited.
44  void validate(const trajectory::Trajectory* traj) override;
45 
48  std::future<void> execute(
49  const trajectory::ConstTrajectoryPtr& traj) override;
50 
54  std::future<void> execute(
55  const trajectory::ConstTrajectoryPtr& traj, const ::ros::Time& startTime);
56 
61  void step(const std::chrono::system_clock::time_point& timepoint) override;
62 
64  void cancel() override;
65 
66 private:
68  = actionlib::ActionClient<control_msgs::FollowJointTrajectoryAction>;
69  using GoalHandle = TrajectoryActionClient::GoalHandle;
70 
71  void transitionCallback(GoalHandle handle);
72 
73  ::ros::NodeHandle mNode;
74  ::ros::CallbackQueue mCallbackQueue;
76  TrajectoryActionClient::GoalHandle mGoalHandle;
77 
80 
81  std::chrono::milliseconds mConnectionTimeout;
82  std::chrono::milliseconds mConnectionPollingPeriod;
83 
85  std::unique_ptr<std::promise<void>> mPromise;
86 
88  mutable std::mutex mMutex;
89 };
90 
91 } // namespace ros
92 } // namespace control
93 } // namespace aikido
94 
95 #endif // ifndef AIKIDO_CONTROL_ROS_ROSTRAJECTORYEXECUTOR_HPP_
aikido::control::ros::RosTrajectoryExecutor::RosTrajectoryExecutor
RosTrajectoryExecutor(::ros::NodeHandle node, const std::string &serverName, double waypointTimestep, double goalTimeTolerance, const std::chrono::milliseconds &connectionTimeout=std::chrono::milliseconds{1000}, const std::chrono::milliseconds &connectionPollingPeriod=std::chrono::milliseconds{20})
Constructor.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::control::ros::RosTrajectoryExecutor::mGoalHandle
TrajectoryActionClient::GoalHandle mGoalHandle
Definition: RosTrajectoryExecutor.hpp:76
aikido::control::ros::RosTrajectoryExecutor::validate
void validate(const trajectory::Trajectory *traj) override
Validate the traj in preparation for execution.
aikido::control::ros::RosTrajectoryExecutor::~RosTrajectoryExecutor
virtual ~RosTrajectoryExecutor()
aikido::trajectory::ConstTrajectoryPtr
std::shared_ptr< const Trajectory > ConstTrajectoryPtr
Definition: Trajectory.hpp:13
aikido::control::ros::RosTrajectoryExecutor::cancel
void cancel() override
Cancel the current trajectory.
aikido::control::ros::RosTrajectoryExecutor::mClient
TrajectoryActionClient mClient
Definition: RosTrajectoryExecutor.hpp:75
aikido::control::ros::RosTrajectoryExecutor::execute
std::future< void > execute(const trajectory::ConstTrajectoryPtr &traj) override
Sends trajectory to ROS server for execution.
aikido::control::ros::RosTrajectoryExecutor::mMutex
std::mutex mMutex
Manages access to mInProgress, mPromise.
Definition: RosTrajectoryExecutor.hpp:88
aikido::control::ros::RosTrajectoryExecutor::mConnectionPollingPeriod
std::chrono::milliseconds mConnectionPollingPeriod
Definition: RosTrajectoryExecutor.hpp:82
aikido::control::ros::RosTrajectoryExecutor::mPromise
std::unique_ptr< std::promise< void > > mPromise
Definition: RosTrajectoryExecutor.hpp:85
aikido::control::ros::RosTrajectoryExecutor::mNode
::ros::NodeHandle mNode
Definition: RosTrajectoryExecutor.hpp:73
aikido::control::ros::RosTrajectoryExecutor::mCallbackQueue
::ros::CallbackQueue mCallbackQueue
Definition: RosTrajectoryExecutor.hpp:74
aikido::control::ros::RosTrajectoryExecutor::mGoalTimeTolerance
double mGoalTimeTolerance
Definition: RosTrajectoryExecutor.hpp:79
Trajectory.hpp
aikido::control::TrajectoryExecutor
Abstract class for executing trajectories.
Definition: TrajectoryExecutor.hpp:17
aikido::control::ros::RosTrajectoryExecutor::step
void step(const std::chrono::system_clock::time_point &timepoint) override
Step to a point in time.
aikido::control::ros::RosTrajectoryExecutor::TrajectoryActionClient
actionlib::ActionClient< control_msgs::FollowJointTrajectoryAction > TrajectoryActionClient
Definition: RosTrajectoryExecutor.hpp:68
aikido::control::ros::RosTrajectoryExecutor::mConnectionTimeout
std::chrono::milliseconds mConnectionTimeout
Definition: RosTrajectoryExecutor.hpp:81
aikido::control::ros::RosTrajectoryExecutor
This class sends trajectory commands to ROS server.
Definition: RosTrajectoryExecutor.hpp:21
aikido::control::ros::RosTrajectoryExecutor::mInProgress
bool mInProgress
Definition: RosTrajectoryExecutor.hpp:84
TrajectoryExecutor.hpp
aikido::control::ros::RosTrajectoryExecutor::transitionCallback
void transitionCallback(GoalHandle handle)
aikido::trajectory::Trajectory
Time-parameterized path in a StateSpace.
Definition: Trajectory.hpp:20
aikido::control::ros::RosTrajectoryExecutor::GoalHandle
TrajectoryActionClient::GoalHandle GoalHandle
Definition: RosTrajectoryExecutor.hpp:69
aikido::control::ros::RosTrajectoryExecutor::mWaypointTimestep
double mWaypointTimestep
Definition: RosTrajectoryExecutor.hpp:78