37 #ifndef ROBOT_CONTROLLERS_SCALED_MIMIC_H 38 #define ROBOT_CONTROLLERS_SCALED_MIMIC_H 47 #include <control_msgs/GripperCommandAction.h> 89 virtual bool stop(
bool force);
109 return "robot_controllers/ScaledMimicController";
127 #endif // ROBOT_CONTROLLERS_SCALED_MIMIC_H virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
Controller for a having one joint be a (scaled) mimic of another. Primary design use case is making a...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
JointHandlePtr joint_to_mimic_
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual ~ScaledMimicController()
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > server_t
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.
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
JointHandlePtr joint_to_control_