Public Member Functions | Private Attributes | List of all members
ros_controllers_cartesian::PoseCommandHandle Class Reference

A handle for setting pose commands. More...

#include <cartesian_command_interface.h>

Inheritance diagram for ros_controllers_cartesian::PoseCommandHandle:
Inheritance graph
[legend]

Public Member Functions

geometry_msgs::Pose getCommand () const
 
const geometry_msgs::Pose * getCommandPtr () const
 
 PoseCommandHandle ()=default
 
 PoseCommandHandle (const CartesianStateHandle &state_handle, geometry_msgs::Pose *cmd)
 
void setCommand (const geometry_msgs::Pose &pose)
 
virtual ~PoseCommandHandle ()=default
 
- Public Member Functions inherited from ros_controllers_cartesian::CartesianStateHandle
 CartesianStateHandle ()=default
 
 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)
 
geometry_msgs::Accel getAccel () const
 
geometry_msgs::Accel getJerk () const
 
std::string getName () const
 
geometry_msgs::Pose getPose () const
 
geometry_msgs::Twist getTwist () const
 
virtual ~CartesianStateHandle ()=default
 

Private Attributes

geometry_msgs::Pose * cmd_ = { nullptr }
 

Detailed Description

A handle for setting pose commands.

Cartesian ROS-controllers can use this handle to write their control signals to the according PoseCommandInterface.

Definition at line 39 of file cartesian_command_interface.h.

Constructor & Destructor Documentation

◆ PoseCommandHandle() [1/2]

ros_controllers_cartesian::PoseCommandHandle::PoseCommandHandle ( )
default

◆ PoseCommandHandle() [2/2]

ros_controllers_cartesian::PoseCommandHandle::PoseCommandHandle ( const CartesianStateHandle state_handle,
geometry_msgs::Pose *  cmd 
)
inline

Definition at line 43 of file cartesian_command_interface.h.

◆ ~PoseCommandHandle()

virtual ros_controllers_cartesian::PoseCommandHandle::~PoseCommandHandle ( )
virtualdefault

Member Function Documentation

◆ getCommand()

geometry_msgs::Pose ros_controllers_cartesian::PoseCommandHandle::getCommand ( ) const
inline

Definition at line 60 of file cartesian_command_interface.h.

◆ getCommandPtr()

const geometry_msgs::Pose* ros_controllers_cartesian::PoseCommandHandle::getCommandPtr ( ) const
inline

Definition at line 65 of file cartesian_command_interface.h.

◆ setCommand()

void ros_controllers_cartesian::PoseCommandHandle::setCommand ( const geometry_msgs::Pose &  pose)
inline

Definition at line 54 of file cartesian_command_interface.h.

Member Data Documentation

◆ cmd_

geometry_msgs::Pose* ros_controllers_cartesian::PoseCommandHandle::cmd_ = { nullptr }
private

Definition at line 72 of file cartesian_command_interface.h.


The documentation for this class was generated from the following file:


cartesian_interface
Author(s):
autogenerated on Thu Feb 23 2023 03:10:45