A handle for setting twist commands.
More...
#include <cartesian_command_interface.h>
|
geometry_msgs::Twist * | cmd_ = { nullptr } |
|
A handle for setting twist commands.
Cartesian ROS-controllers can use this handle to write their control signals to the according TwistCommandInterface.
Definition at line 81 of file cartesian_command_interface.h.
◆ TwistCommandHandle() [1/2]
ros_controllers_cartesian::TwistCommandHandle::TwistCommandHandle |
( |
| ) |
|
|
default |
◆ TwistCommandHandle() [2/2]
ros_controllers_cartesian::TwistCommandHandle::TwistCommandHandle |
( |
const CartesianStateHandle & |
state_handle, |
|
|
geometry_msgs::Twist * |
cmd |
|
) |
| |
|
inline |
◆ ~TwistCommandHandle()
virtual ros_controllers_cartesian::TwistCommandHandle::~TwistCommandHandle |
( |
| ) |
|
|
virtualdefault |
◆ getCommand()
geometry_msgs::Twist ros_controllers_cartesian::TwistCommandHandle::getCommand |
( |
| ) |
const |
|
inline |
◆ getCommandPtr()
const geometry_msgs::Twist* ros_controllers_cartesian::TwistCommandHandle::getCommandPtr |
( |
| ) |
const |
|
inline |
◆ setCommand()
void ros_controllers_cartesian::TwistCommandHandle::setCommand |
( |
const geometry_msgs::Twist & |
twist | ) |
|
|
inline |
◆ cmd_
geometry_msgs::Twist* ros_controllers_cartesian::TwistCommandHandle::cmd_ = { nullptr } |
|
private |
The documentation for this class was generated from the following file: