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;}
46 PosIface* pos_iface = robot_hw->
get<PosIface>();
47 EffIface* eff_iface = robot_hw->
get<EffIface>();
52 for (
const auto& pos_joint : pos_joints)
54 pos_cmd_.push_back(pos_iface->getHandle(pos_joint));
59 ROS_WARN(
"Optional interface not found: 'hardware_interface::PositionJointInterface'");
64 for (
const auto& eff_joint : eff_joints)
66 eff_cmd_.push_back(eff_iface->getHandle(eff_joint));
71 ROS_ERROR(
"Required interface not found: 'hardware_interface::EffortJointInterface'");
80 ROS_INFO(
"Starting PosEffOptController");
88 ROS_INFO(
"Stopping PosEffOptController");
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n) override
void update(const ros::Time &time, const ros::Duration &period) override
void starting(const ros::Time &time) override
std::vector< hardware_interface::JointHandle > eff_cmd_
bool getParam(const std::string &key, std::string &s) const
std::vector< hardware_interface::JointHandle > pos_cmd_
void stopping(const ros::Time &time) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)