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;
47 PosIface* pos_iface = robot_hw->
get<PosIface>();
48 EffIface* eff_iface = robot_hw->
get<EffIface>();
53 for (NamesIterator it = pos_joints.begin(); it != pos_joints.end(); it++)
55 pos_cmd_.push_back(pos_iface->getHandle(*it));
60 ROS_WARN(
"Optional interface not found: 'hardware_interface::PositionJointInterface'");
65 for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++)
67 eff_cmd_.push_back(eff_iface->getHandle(*it));
72 ROS_ERROR(
"Required interface not found: 'hardware_interface::EffortJointInterface'");
81 ROS_INFO(
"Starting PosEffOptController");
89 ROS_INFO(
"Stopping PosEffOptController");
void stopping(const ros::Time &time)
std::vector< hardware_interface::JointHandle > eff_cmd_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n)
std::vector< hardware_interface::JointHandle > pos_cmd_
void update(const ros::Time &time, const ros::Duration &period)
void starting(const ros::Time &time)
bool getParam(const std::string &key, std::string &s) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)