Publishes a static transform into the tf2 buffer.
More...
#include <publish_velocity_force_command.hpp>
Publishes a static transform into the tf2 buffer.
Data Port Name | Port Type | Object Type |
velocity_force_controller_command_topic | input | std::string |
velocity_controlled_axes | input | std::vector<int> |
force_controlled_axes | input | std::vector<int> |
wrench_gain | input | double |
twist_stamped | input | geometry_msgs::msg::TwistStamped |
wrench_stamped | input | geometry_msgs::msg::WrenchStamped |
publish_rate | input | int |
◆ VelocityForceCommand
◆ PublishVelocityForceCommand()
moveit_studio::behaviors::PublishVelocityForceCommand::PublishVelocityForceCommand |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::PublishVelocityForceCommand::metadata |
( |
| ) |
|
|
static |
◆ onHalted()
void moveit_studio::behaviors::PublishVelocityForceCommand::onHalted |
( |
| ) |
|
|
override |
◆ onRunning()
BT::NodeStatus moveit_studio::behaviors::PublishVelocityForceCommand::onRunning |
( |
| ) |
|
|
override |
◆ onStart()
BT::NodeStatus moveit_studio::behaviors::PublishVelocityForceCommand::onStart |
( |
| ) |
|
|
override |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::PublishVelocityForceCommand::providedPorts |
( |
| ) |
|
|
static |
The documentation for this class was generated from the following files: