Go to the documentation of this file.    1 #ifndef AIKIDO_CONTROL_ROS_ROSTRAJECTORYEXECUTOR_HPP_ 
    2 #define AIKIDO_CONTROL_ROS_ROSTRAJECTORYEXECUTOR_HPP_ 
    8 #include <actionlib/client/action_client.h> 
    9 #include <control_msgs/FollowJointTrajectoryAction.h> 
   10 #include <ros/callback_queue.h> 
   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});
 
   61   void step(
const std::chrono::system_clock::time_point& timepoint) 
override;
 
   68       = actionlib::ActionClient<control_msgs::FollowJointTrajectoryAction>;
 
   95 #endif // ifndef AIKIDO_CONTROL_ROS_ROSTRAJECTORYEXECUTOR_HPP_ 
 
 
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.
 
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
 
TrajectoryActionClient::GoalHandle mGoalHandle
Definition: RosTrajectoryExecutor.hpp:76
 
void validate(const trajectory::Trajectory *traj) override
Validate the traj in preparation for execution.
 
virtual ~RosTrajectoryExecutor()
 
std::shared_ptr< const Trajectory > ConstTrajectoryPtr
Definition: Trajectory.hpp:13
 
void cancel() override
Cancel the current trajectory.
 
TrajectoryActionClient mClient
Definition: RosTrajectoryExecutor.hpp:75
 
std::future< void > execute(const trajectory::ConstTrajectoryPtr &traj) override
Sends trajectory to ROS server for execution.
 
std::mutex mMutex
Manages access to mInProgress, mPromise.
Definition: RosTrajectoryExecutor.hpp:88
 
std::chrono::milliseconds mConnectionPollingPeriod
Definition: RosTrajectoryExecutor.hpp:82
 
std::unique_ptr< std::promise< void > > mPromise
Definition: RosTrajectoryExecutor.hpp:85
 
::ros::NodeHandle mNode
Definition: RosTrajectoryExecutor.hpp:73
 
::ros::CallbackQueue mCallbackQueue
Definition: RosTrajectoryExecutor.hpp:74
 
double mGoalTimeTolerance
Definition: RosTrajectoryExecutor.hpp:79
 
Abstract class for executing trajectories.
Definition: TrajectoryExecutor.hpp:17
 
void step(const std::chrono::system_clock::time_point &timepoint) override
Step to a point in time.
 
actionlib::ActionClient< control_msgs::FollowJointTrajectoryAction > TrajectoryActionClient
Definition: RosTrajectoryExecutor.hpp:68
 
std::chrono::milliseconds mConnectionTimeout
Definition: RosTrajectoryExecutor.hpp:81
 
This class sends trajectory commands to ROS server.
Definition: RosTrajectoryExecutor.hpp:21
 
bool mInProgress
Definition: RosTrajectoryExecutor.hpp:84
 
void transitionCallback(GoalHandle handle)
 
Time-parameterized path in a StateSpace.
Definition: Trajectory.hpp:20
 
TrajectoryActionClient::GoalHandle GoalHandle
Definition: RosTrajectoryExecutor.hpp:69
 
double mWaypointTimestep
Definition: RosTrajectoryExecutor.hpp:78