![]() |
ros2_control - foxy
|
#include <joint_limits_interface.hpp>


Public Member Functions | |
| JointLimitHandle (const hardware_interface::JointHandle &jposh, const hardware_interface::JointHandle &jcmdh, const JointLimits &limits) | |
| JointLimitHandle (const hardware_interface::JointHandle &jposh, const hardware_interface::JointHandle &jvelh, const hardware_interface::JointHandle &jcmdh, const JointLimits &limits) | |
| std::string | get_name () const |
| virtual void | enforce_limits (const rclcpp::Duration &period)=0 |
| Sub-class implementation of limit enforcing policy. | |
| virtual void | reset () |
| Clear stored state, causing it to reset next iteration. | |
Protected Member Functions | |
| double | get_velocity (const rclcpp::Duration &period) const |
| Return velocity for limit calculations. | |
Protected Attributes | |
| hardware_interface::JointHandle | jposh_ |
| hardware_interface::JointHandle | jvelh_ |
| hardware_interface::JointHandle | jcmdh_ |
| joint_limits_interface::JointLimits | limits_ |
| double | prev_pos_ |
| double | prev_vel_ |
The base class of limit handles for enforcing position, velocity, and effort limits of an effort-controlled joint.
|
pure virtual |
Sub-class implementation of limit enforcing policy.
Implemented in joint_limits_interface::PositionJointSaturationHandle, joint_limits_interface::VelocityJointSoftLimitsHandle, joint_limits_interface::PositionJointSoftLimitsHandle, joint_limits_interface::EffortJointSaturationHandle, joint_limits_interface::EffortJointSoftLimitsHandle, and joint_limits_interface::VelocityJointSaturationHandle.
|
inline |
|
inlineprotected |
Return velocity for limit calculations.
| period | Time since last measurement |