28 #ifndef QB_DEVICE_JOINT_LIMITS_INTERFACE_H 29 #define QB_DEVICE_JOINT_LIMITS_INTERFACE_H 64 double min_pos, max_pos;
205 for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it) {
228 #endif // QB_DEVICE_JOINT_LIMITS_INTERFACE_H
A handle used to enforce position and velocity limits of a position-controlled joint.
void enforceLimits(const ros::Duration &period)
Enforce position and velocity limits for a joint that is not subject to soft limits.
std::string getName() const
std::string getName() const
double getCommand() const
joint_limits_interface::JointLimits * limits_
void reset()
Reset all managed handles.
void reset()
Reset the interface state.
ROSLIB_DECL std::string command(const std::string &cmd)
#define ROS_WARN_STREAM_COND(cond, args)
double getPosition() const
void setCommand(double command)
PositionJointSaturationHandle(const hardware_interface::JointHandle &joint_handle, joint_limits_interface::JointLimits *limits)
Construct the saturation handle with dynamic joint limits.
A handle used to enforce position and velocity limits of a position-controlled joint that does not ha...
hardware_interface::JointHandle joint_handle_
T saturate(const T val, const T min_val, const T max_val)