38 #ifndef ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H 39 #define ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H 43 #include <boost/shared_ptr.hpp> 44 #include <boost/thread.hpp> 50 #include <control_msgs/FollowJointTrajectoryAction.h> 96 virtual bool stop(
bool force);
104 virtual bool reset();
116 return "robot_controllers/FollowJointTrajectoryController";
127 void executeCb(
const control_msgs::FollowJointTrajectoryGoalConstPtr&
goal);
171 #endif // ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H_ Basis for a Trajectory Point.
boost::shared_ptr< TrajectorySampler > sampler_
control_msgs::FollowJointTrajectoryFeedback feedback_
TrajectoryPoint goal_tolerance_
virtual ~FollowJointTrajectoryController()
This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) rob...
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
FollowJointTrajectoryController()
TrajectoryPoint path_tolerance_
bool stop_on_path_violation_
virtual std::string getType()
Get the type of this controller.
void executeCb(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
Callback for goal.
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > server_t
boost::shared_ptr< server_t > server_
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
boost::mutex sampler_mutex_
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
TrajectoryPoint last_sample_
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
ControllerManager * manager_
std::vector< std::string > joint_names_
std::vector< JointHandlePtr > joints_
std::vector< bool > continuous_
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
TrajectoryPoint getPointFromCurrent(bool incl_vel, bool incl_acc, bool zero_vel)
Get a trajectory point from the current position/velocity/acceleration.
double goal_time_tolerance_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.