48 : name_(
"generic_hw_interface"), nh_(nh), use_rosparam_joint_limits_(false), use_soft_limits_if_available_(false)
51 if (urdf_model == NULL)
58 nh_,
"hardware_interface");
59 std::size_t error = 0;
85 for (std::size_t joint_id = 0; joint_id <
num_joints_; ++joint_id)
108 registerJointLimits(joint_handle_position, joint_handle_velocity, joint_handle_effort, joint_id);
122 std::size_t joint_id)
133 bool has_joint_limits =
false;
134 bool has_soft_limits =
false;
147 if (urdf_joint == NULL)
156 has_joint_limits =
true;
165 if (urdf_joint->type != urdf::Joint::CONTINUOUS)
167 <<
" does not have a URDF " 176 has_joint_limits =
true;
190 has_soft_limits =
true;
196 <<
" does not have soft joint " 202 if (!has_joint_limits)
211 joint_limits.
min_position += std::numeric_limits<double>::epsilon();
212 joint_limits.
max_position -= std::numeric_limits<double>::epsilon();
234 joint_limits, soft_limits);
237 joint_limits, soft_limits);
274 std::stringstream ss;
275 std::cout.precision(15);
288 std::stringstream ss;
289 std::cout.precision(15);
290 ss <<
" position velocity effort \n";
302 std::string urdf_string;
306 while (urdf_string.empty() &&
ros::ok())
308 std::string search_param_name;
312 << search_param_name);
313 nh.
getParam(search_param_name, urdf_string);
319 nh.
getParam(param_name, urdf_string);
void registerInterface(T *iface)
hardware_interface::EffortJointInterface effort_joint_interface_
std::vector< double > joint_position_command_
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
hardware_interface::JointStateInterface joint_state_interface_
#define ROS_INFO_STREAM_THROTTLE(period, args)
bool use_rosparam_joint_limits_
std::vector< double > joint_position_lower_limits_
bool use_soft_limits_if_available_
std::vector< double > joint_effort_limits_
#define ROS_INFO_STREAM_NAMED(name, args)
joint_limits_interface::EffortJointSaturationInterface eff_jnt_sat_interface_
virtual void init()
Initialize the hardware interface.
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
std::vector< double > joint_effort_
virtual void registerJointLimits(const hardware_interface::JointHandle &joint_handle_position, const hardware_interface::JointHandle &joint_handle_velocity, const hardware_interface::JointHandle &joint_handle_effort, std::size_t joint_id)
Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved fro...
joint_limits_interface::VelocityJointSaturationInterface vel_jnt_sat_interface_
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
bool getParam(const std::string &key, std::string &s) const
virtual void printState()
Helper for debugging a joint's state.
hardware_interface::VelocityJointInterface velocity_joint_interface_
joint_limits_interface::EffortJointSoftLimitsInterface eff_jnt_soft_limits_
std::vector< std::string > joint_names_
joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_soft_limits_
virtual void reset()
Set all members to default values.
std::string printCommandHelper()
Helper for debugging a joint's command.
std::vector< double > joint_position_upper_limits_
void registerHandle(const JointStateHandle &handle)
std::vector< double > joint_effort_command_
bool searchParam(const std::string &key, std::string &result) const
JointStateHandle getHandle(const std::string &name)
GenericHWInterface(const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
virtual void loadURDF(const ros::NodeHandle &nh, std::string param_name)
Get the URDF XML from the parameter server.
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
const std::string & getNamespace() const
std::string printStateHelper()
urdf::Model * urdf_model_
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
std::vector< double > joint_velocity_limits_
joint_limits_interface::VelocityJointSoftLimitsInterface vel_jnt_soft_limits_
std::vector< double > joint_position_
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
hardware_interface::PositionJointInterface position_joint_interface_
joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_
#define ROS_WARN_STREAM_NAMED(name, args)