1 #ifndef __ROS_CONTROL_INTERFACE__ 2 #define __ROS_CONTROL_INTERFACE__ 21 template <
class Jo
intInterface>
51 std::vector<hardware_interface::JointHandle>
joints_;
56 template <
class Jo
intInterface>
62 JointInterface* hw =
new JointInterface();
64 dynamic_cast<hardware_interface::EffortJointInterface*>(hw))
69 dynamic_cast<hardware_interface::VelocityJointInterface*>(hw))
74 dynamic_cast<hardware_interface::PositionJointInterface*>(hw))
80 throw std::logic_error(
"UNKNOWN JOINT INTERFACE TYPE");
84 template <
class Jo
intInterface>
103 if (!urdf.
initParam(
"robot_description"))
109 for (
unsigned int i = 0; i <
n_joints_; i++)
111 const std::string& name = joint_names_[i];
115 joints_.push_back(hw->getHandle(name));
122 urdf::JointConstSharedPtr joint_urdf = urdf.getJoint(name);
125 ROS_ERROR(
"Could not find joint '%s' in urdf", name.c_str());
134 template <
class Jo
intInterface>
140 template <
class Jo
intInterface>
144 sensor_msgs::JointState curr_state,
command;
146 for (
unsigned int i = 0; i <
n_joints_; i++)
149 curr_state.position.push_back(
joints_[i].getPosition());
150 curr_state.velocity.push_back(
joints_[i].getVelocity());
151 curr_state.effort.push_back(
joints_[i].getEffort());
154 command =
controller_->updateControl(curr_state, period);
156 for (
unsigned int i = 0; i <
n_joints_; i++)
160 for (
unsigned int j = 0; j < command.name.size(); j++)
162 if (command.name[j] == name)
167 joints_[i].setCommand(command.effort[j]);
170 joints_[i].setCommand(command.velocity[j]);
173 joints_[i].setCommand(command.position[j]);
181 template <
class Jo
intInterface>
virtual const char * what() const
ROSLIB_DECL std::string command(const std::string &cmd)
const std::string & getNamespace() const
URDF_EXPORT bool initParam(const std::string ¶m)
#define ROS_ERROR_STREAM(args)