57 std::string mimic, controlled;
58 nh.
param<std::string>(
"mimic_joint", mimic,
"torso_lift_joint");
59 nh.
param<std::string>(
"controlled_joint", controlled,
"bellows_joint");
68 nh.
param(
"autostart", autostart,
false);
80 "Unable to start, not initialized.");
108 std::vector<std::string> names;
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 int requestStart(const std::string &name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
#define ROS_ERROR_NAMED(name,...)
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
JointHandlePtr getJointHandle(const std::string &name)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
JointHandlePtr joint_to_control_