42 std::string robot_description;
43 if (!robot_hw_nh.
getParam(
"robot_description", robot_description)) {
return false;}
48 std::vector<std::string> joints;
49 joints.push_back(
"right_arm_joint_1");
52 size_t nb_joints = joints.size();
60 for (
size_t i = 0; i < nb_joints; i++)
void registerInterface(T *iface)
std::vector< double > joint_velocity_
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
std::vector< std::string > joint_name_
std::vector< double > joint_position_
hardware_interface::EffortJointInterface ej_interface_
void read(const ros::Time &time, const ros::Duration &period)
void write(const ros::Time &time, const ros::Duration &period)
std::vector< double > joint_effort_
std::vector< double > joint_velocity_command_
void registerHandle(const JointStateHandle &handle)
hardware_interface::VelocityJointInterface vj_interface_
JointStateHandle getHandle(const std::string &name)
hardware_interface::JointStateInterface js_interface_
bool getParam(const std::string &key, std::string &s) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::vector< double > joint_effort_command_