Go to the documentation of this file.
36 #include <control_msgs/FollowJointTrajectoryGoal.h>
37 #include <control_msgs/JointTolerance.h>
38 #include <trajectory_msgs/JointTrajectoryPoint.h>
39 #include <control_msgs/FollowJointTrajectoryAction.h>
42 #include <cartesian_control_msgs/CartesianTolerance.h>
43 #include <cartesian_control_msgs/CartesianTrajectoryPoint.h>
44 #include <cartesian_control_msgs/FollowCartesianTrajectoryGoal.h>
45 #include <cartesian_control_msgs/FollowCartesianTrajectoryAction.h>
57 using Tolerance = std::vector<control_msgs::JointTolerance>;
62 using GoalConstPtr = control_msgs::FollowJointTrajectoryGoalConstPtr;
67 using Tolerance = cartesian_control_msgs::CartesianTolerance;
72 using GoalConstPtr = cartesian_control_msgs::FollowCartesianTrajectoryGoalConstPtr;
105 template <
class TrajectoryInterface>
108 scaled_controllers::SpeedScalingInterface>,
109 public std::conditional<std::is_same<TrajectoryInterface, hardware_interface::JointTrajectoryInterface>::value,
110 JointBase, CartesianBase>::type
124 typename std::conditional<std::is_same<TrajectoryInterface, hardware_interface::JointTrajectoryInterface>::value,
152 void executeCB(
const typename Base::GoalConstPtr& goal);
201 bool withinTolerances(
const typename Base::TrajectoryPoint& error,
const typename Base::Tolerance& tolerances);
210 bool isValid(
const typename Base::GoalConstPtr& goal);
224 std::unique_ptr<actionlib::SimpleActionServer<typename Base::FollowTrajectoryAction> >
action_server_;
cartesian_control_msgs::FollowCartesianTrajectoryFeedback CartesianTrajectoryFeedback
FeedbackType for Cartesian trajectories.
hardware_interface::JointTrajectoryFeedback TrajectoryFeedback
void starting(const ros::Time &time)
control_msgs::FollowJointTrajectoryResult FollowTrajectoryResult
std::atomic< bool > done_
trajectory_msgs::JointTrajectoryPoint TrajectoryPoint
ActionDuration action_duration_
std::unique_ptr< scaled_controllers::SpeedScalingHandle > speed_scaling_
std::vector< control_msgs::JointTolerance > Tolerance
cartesian_control_msgs::CartesianTrajectoryPoint TrajectoryPoint
void executeCB(const typename Base::GoalConstPtr &goal)
Callback method for new action goals.
control_msgs::FollowJointTrajectoryAction FollowTrajectoryAction
Container for easy time management.
hardware_interface::CartesianTrajectoryFeedback TrajectoryFeedback
void update(const ros::Time &time, const ros::Duration &period)
bool init(hardware_interface::RobotHW *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
bool withinTolerances(const typename Base::TrajectoryPoint &error, const typename Base::Tolerance &tolerances)
Check if tolerances are met.
std::unique_ptr< actionlib::SimpleActionServer< typename Base::FollowTrajectoryAction > > action_server_
cartesian_control_msgs::CartesianTolerance Tolerance
TrajectoryInterface * trajectory_interface_
void preemptCB()
Callback method for preempt requests.
ExecutionState
Hardware-generic done flags for trajectory execution.
MultiInterfaceController(bool allow_optional_interfaces=false)
cartesian_control_msgs::FollowCartesianTrajectoryResult FollowTrajectoryResult
void stopping(const ros::Time &time)
control_msgs::FollowJointTrajectoryGoalConstPtr GoalConstPtr
control_msgs::FollowJointTrajectoryFeedback JointTrajectoryFeedback
FeedbackType for joint-based trajectories.
std::vector< std::string > joint_names_
cartesian_control_msgs::FollowCartesianTrajectoryGoalConstPtr GoalConstPtr
ros::Duration current
Real duration of the current action.
Base::Tolerance path_tolerances_
bool isValid(const typename Base::GoalConstPtr &goal)
Check if follow trajectory goals are valid.
A ROS controller for forwarding trajectories to a robot for interpolation.
Base::Tolerance goal_tolerances_
cartesian_control_msgs::FollowCartesianTrajectoryAction FollowTrajectoryAction
ros::Duration target
Target duration of the current action.
void monitorExecution(const typename Base::TrajectoryFeedback &feedback)
Monitor the trajectory execution.
void doneCB(const hardware_interface::ExecutionState &state)
Will get called upon finishing the forwarded trajectory.