34 std::vector<std::string> pos_joints;
35 if (!n.
getParam(
"position_joints", pos_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 PosIface* pos_iface = robot_hw->
get<PosIface>();
46 EffIface* eff_iface = robot_hw->
get<EffIface>();
49 for (NamesIterator it = pos_joints.begin(); it != pos_joints.end(); it++)
51 pos_cmd_.push_back(pos_iface->getHandle(*it));
54 for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++)
56 eff_cmd_.push_back(eff_iface->getHandle(*it));
64 ROS_INFO(
"Starting PosEffController");
72 ROS_INFO(
"Stopping PosEffController");
std::vector< hardware_interface::JointHandle > pos_cmd_
std::vector< hardware_interface::JointHandle > eff_cmd_
void update(const ros::Time &time, const ros::Duration &period)
void stopping(const ros::Time &time)
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n)
bool getParam(const std::string &key, std::string &s) const
void starting(const ros::Time &time)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)