A state handle for Cartesian hardware interfaces.
More...
#include <cartesian_state_handle.h>
A state handle for Cartesian hardware interfaces.
Cartesian ROS-controllers can use this handle to read the current Cartesian state from the Cartesian HW-interface and use that in their control loops. The functionality is analog to how the joint-based handles work: Implementers of the hardware_interface::RobotHW class provide a set of buffers to this handle upon instantiation and register this handle with an instance of the according CartesianStateInterface.
Definition at line 48 of file cartesian_state_handle.h.
◆ CartesianStateHandle() [1/2]
ros_controllers_cartesian::CartesianStateHandle::CartesianStateHandle |
( |
| ) |
|
|
default |
◆ CartesianStateHandle() [2/2]
ros_controllers_cartesian::CartesianStateHandle::CartesianStateHandle |
( |
const std::string & |
ref_frame_id, |
|
|
const std::string & |
frame_id, |
|
|
const geometry_msgs::Pose * |
pose, |
|
|
const geometry_msgs::Twist * |
twist, |
|
|
const geometry_msgs::Accel * |
accel, |
|
|
const geometry_msgs::Accel * |
jerk |
|
) |
| |
|
inline |
◆ ~CartesianStateHandle()
virtual ros_controllers_cartesian::CartesianStateHandle::~CartesianStateHandle |
( |
| ) |
|
|
virtualdefault |
◆ getAccel()
geometry_msgs::Accel ros_controllers_cartesian::CartesianStateHandle::getAccel |
( |
| ) |
const |
|
inline |
◆ getJerk()
geometry_msgs::Accel ros_controllers_cartesian::CartesianStateHandle::getJerk |
( |
| ) |
const |
|
inline |
◆ getName()
std::string ros_controllers_cartesian::CartesianStateHandle::getName |
( |
| ) |
const |
|
inline |
◆ getPose()
geometry_msgs::Pose ros_controllers_cartesian::CartesianStateHandle::getPose |
( |
| ) |
const |
|
inline |
◆ getTwist()
geometry_msgs::Twist ros_controllers_cartesian::CartesianStateHandle::getTwist |
( |
| ) |
const |
|
inline |
◆ accel_
const geometry_msgs::Accel* ros_controllers_cartesian::CartesianStateHandle::accel_ |
|
private |
◆ frame_id_
std::string ros_controllers_cartesian::CartesianStateHandle::frame_id_ |
|
private |
◆ jerk_
const geometry_msgs::Accel* ros_controllers_cartesian::CartesianStateHandle::jerk_ |
|
private |
◆ pose_
const geometry_msgs::Pose* ros_controllers_cartesian::CartesianStateHandle::pose_ |
|
private |
◆ ref_frame_id_
std::string ros_controllers_cartesian::CartesianStateHandle::ref_frame_id_ |
|
private |
◆ twist_
const geometry_msgs::Twist* ros_controllers_cartesian::CartesianStateHandle::twist_ |
|
private |
The documentation for this class was generated from the following file: