38 #ifndef ROBOT_CONTROLLERS_POINT_HEAD_H 39 #define ROBOT_CONTROLLERS_POINT_HEAD_H 49 #include <control_msgs/PointHeadAction.h> 55 #include <kdl/tree.hpp> 91 virtual bool stop(
bool force);
111 return "robot_controllers/PointHeadController";
121 void executeCb(
const control_msgs::PointHeadGoalConstPtr&
goal);
153 #endif // ROBOT_CONTROLLERS_POINT_HEAD_H Basis for a Trajectory Point.
control_msgs::PointHeadResult result_
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
virtual ~PointHeadController()
std::string root_link_
action was preempted (has nothing to do with preempt() above
TrajectoryPoint last_sample_
actionlib::SimpleActionServer< control_msgs::PointHeadAction > head_server_t
JointHandlePtr head_tilt_
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
tf::TransformListener listener_
boost::shared_ptr< TrajectorySampler > sampler_
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
void executeCb(const control_msgs::PointHeadGoalConstPtr &goal)
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
boost::shared_ptr< head_server_t > server_
ControllerManager * manager_
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
virtual std::string getType()
Get the type of this controller.
boost::mutex sampler_mutex_
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.