37 #ifndef ROBOT_CONTROLLERS_PARALLEL_GRIPPER_H 38 #define ROBOT_CONTROLLERS_PARALLEL_GRIPPER_H 48 #include <control_msgs/GripperCommandAction.h> 91 virtual bool stop(
bool force);
111 return "robot_controllers/ParallelGripperController";
121 void executeCb(
const control_msgs::GripperCommandGoalConstPtr&
goal);
138 #endif // ROBOT_CONTROLLERS_PARALLEL_GRIPPER_H
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > server_t
virtual ~ParallelGripperController()
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
ControllerManager * manager_
Controller for a parallel jaw gripper, is really only intended for use in simulation.
virtual std::string getType()
Get the type of this controller.
ParallelGripperController()
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
robot_controllers::PID centering_pid_
bool use_centering_controller_
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
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.
void executeCb(const control_msgs::GripperCommandGoalConstPtr &goal)
boost::shared_ptr< server_t > server_