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;}
44 PosIface* pos_iface = robot_hw->
get<PosIface>();
45 EffIface* eff_iface = robot_hw->
get<EffIface>();
48 for (
const auto& pos_joint : pos_joints)
50 pos_cmd_.push_back(pos_iface->getHandle(pos_joint));
53 for (
const auto& eff_joint : eff_joints)
55 eff_cmd_.push_back(eff_iface->getHandle(eff_joint));
63 ROS_INFO(
"Starting PosEffController");
71 ROS_INFO(
"Stopping PosEffController");
std::vector< hardware_interface::JointHandle > pos_cmd_
std::vector< hardware_interface::JointHandle > eff_cmd_
void stopping(const ros::Time &time) override
void update(const ros::Time &time, const ros::Duration &period) override
bool getParam(const std::string &key, std::string &s) const
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void starting(const ros::Time &time) override