35 #ifndef PR2_GRIPPER_CONTROLLER_H__ 36 #define PR2_GRIPPER_CONTROLLER_H__ 66 #include <boost/scoped_ptr.hpp> 67 #include <boost/thread/condition.hpp> 70 #include <std_msgs/Float64.h> 72 #include <pr2_controllers_msgs/JointControllerState.h> 73 #include <pr2_controllers_msgs/Pr2GripperCommand.h> 88 using namespace pr2_controllers_msgs;
89 Pr2GripperCommandPtr c(
new Pr2GripperCommand);
116 void commandCB(
const pr2_controllers_msgs::Pr2GripperCommandConstPtr& msg);
void commandCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr &msg)
realtime_tools::RealtimeBox< pr2_controllers_msgs::Pr2GripperCommandConstPtr > command_box_
ros::Subscriber sub_command_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
virtual void update()
Issues commands to the joint. Should be called at regular intervals.
pr2_mechanism_model::RobotState * robot_
control_toolbox::Pid pid_
pr2_mechanism_model::JointState * joint_state_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_