![]() |
ros2_control - humble
|
A handle used to enforce velocity and acceleration limits of a velocity-controlled joint. More...
#include <joint_limits_interface.hpp>


Public Member Functions | |
| VelocityJointSaturationHandle (const hardware_interface::JointHandle &jvelh, const hardware_interface::JointHandle &jcmdh, const joint_limits_interface::JointLimits &limits) | |
| VelocityJointSaturationHandle (const hardware_interface::JointHandle &jcmdh, const joint_limits_interface::JointLimits &limits) | |
| void | enforce_limits (const rclcpp::Duration &period) override |
| Enforce joint velocity and acceleration limits. | |
Public Member Functions inherited from joint_limits_interface::JointLimitHandle | |
| 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 | reset () |
| Clear stored state, causing it to reset next iteration. | |
Additional Inherited Members | |
Protected Member Functions inherited from joint_limits_interface::JointLimitHandle | |
| double | get_velocity (const rclcpp::Duration &period) const |
| Return velocity for limit calculations. | |
Protected Attributes inherited from joint_limits_interface::JointLimitHandle | |
| hardware_interface::JointHandle | jposh_ |
| hardware_interface::JointHandle | jvelh_ |
| hardware_interface::JointHandle | jcmdh_ |
| joint_limits_interface::JointLimits | limits_ |
| double | prev_pos_ |
| double | prev_vel_ |
A handle used to enforce velocity and acceleration limits of a velocity-controlled joint.
|
inlineoverridevirtual |
Enforce joint velocity and acceleration limits.
| [in] | period | Control period. |
Implements joint_limits_interface::JointLimitHandle.