39   std::vector<std::string> joint_names;
    41   if (!n.
getParam(
"joints", joint_names))
    43     joint_names.push_back(
"hiDOF_joint1");
    44     joint_names.push_back(
"hiDOF_joint2");
    47   for (
unsigned i=0; i<joint_names.size(); i++)
    55   ROS_INFO(
"Starting JointState Controller");
    68   ROS_INFO(
"Stopping JointState Controller");
 
void starting(const ros::Time &)
 
void stopping(const ros::Time &)
 
void update(const ros::Time &, const ros::Duration &)
 
JointHandle getHandle(const std::string &name)
 
bool getParam(const std::string &key, std::string &s) const 
 
std::vector< hardware_interface::JointHandle > joint_effort_commands_
 
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
 
bool init(hardware_interface::EffortJointInterface *hw, ros::NodeHandle &)