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


Public Member Functions | |
| EffortJointSoftLimitsHandle (const hardware_interface::JointHandle &jposh, const hardware_interface::JointHandle &jvelh, const hardware_interface::JointHandle &jcmdh, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits &soft_limits) | |
| EffortJointSoftLimitsHandle (const hardware_interface::JointHandle &jposh, const hardware_interface::JointHandle &jcmdh, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits &soft_limits) | |
| void | enforce_limits (const rclcpp::Duration &period) override |
| Enforce position, velocity and effort limits for a joint subject to soft limits. | |
Public Member Functions inherited from joint_limits_interface::JointSoftLimitsHandle | |
| JointSoftLimitsHandle (const hardware_interface::JointHandle &jposh, const hardware_interface::JointHandle &jcmdh, const JointLimits &limits, const SoftJointLimits &soft_limits) | |
| JointSoftLimitsHandle (const hardware_interface::JointHandle &jposh, const hardware_interface::JointHandle &jvelh, const hardware_interface::JointHandle &jcmdh, const JointLimits &limits, const SoftJointLimits &soft_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::JointSoftLimitsHandle | |
| joint_limits_interface::SoftJointLimits | soft_limits_ |
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 position, velocity and effort limits of an effort-controlled joint.
|
inlineoverridevirtual |
Enforce position, velocity and effort limits for a joint subject to soft limits.
If the joint has no position limits (eg. a continuous joint), only velocity and effort limits will be enforced.
| [in] | period | Control period. |
Implements joint_limits_interface::JointLimitHandle.