calculates a control velocity that is a sum of the target velocity and a catchup velocity. The target motion state can be offset from the incoming motion state message. The returned control velocity is designed to be sent to the velocity_force_controller.
More...
#include <compute_velocity_to_align_with_target.hpp>
calculates a control velocity that is a sum of the target velocity and a catchup velocity. The target motion state can be offset from the incoming motion state message. The returned control velocity is designed to be sent to the velocity_force_controller.
Data Port Name | Port Type | Object Type |
target_motion_state | input | nav_msgs::msg::Odometry |
target_pose_offset | input | geometry_msgs::msg::PoseStamped |
end_effector_frame | input | std::string |
proportional_gain_linear | input | double |
proportional_gain_angular | input | double |
pose_error | output | geometry_msgs::msg::PoseStamped |
control_velocity | output | geometry_msgs::msg::TwistStamped |
◆ ComputeVelocityToAlignWithTarget()
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::ComputeVelocityToAlignWithTarget::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::ComputeVelocityToAlignWithTarget::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
BT::NodeStatus moveit_studio::behaviors::ComputeVelocityToAlignWithTarget::tick |
( |
| ) |
|
|
override |
The documentation for this class was generated from the following files: