34 std::vector<std::string> vel_joints;
35 if (!n.
getParam(
"velocity_joints", vel_joints)) {
return false;}
37 std::vector<std::string> eff_joints;
38 if (!n.
getParam(
"effort_joints", eff_joints)) {
return false;}
40 typedef std::vector<std::string>::const_iterator NamesIterator;
45 VelIface* vel_iface = robot_hw->
get<VelIface>();
46 EffIface* eff_iface = robot_hw->
get<EffIface>();
49 for (NamesIterator it = vel_joints.begin(); it != vel_joints.end(); it++)
51 vel_cmd_.push_back(vel_iface->getHandle(*it));
53 for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++)
55 eff_cmd_.push_back(eff_iface->getHandle(*it));
64 ROS_INFO(
"Starting VelEffController");
72 ROS_INFO(
"Stopping VelEffController");
void starting(const ros::Time &time)
std::vector< hardware_interface::JointHandle > eff_cmd_
std::vector< hardware_interface::JointHandle > vel_cmd_
bool getParam(const std::string &key, std::string &s) const
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n)
void update(const ros::Time &time, const ros::Duration &period)
void stopping(const ros::Time &time)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)