Go to the documentation of this file.
49 state_handle.
getName() +
"'. Command data pointer is null.");
72 geometry_msgs::Pose*
cmd_ = {
nullptr };
91 state_handle.
getName() +
"'. Command data pointer is null.");
114 geometry_msgs::Twist*
cmd_ = {
nullptr };
std::string getName() const
A state handle for Cartesian hardware interfaces.
A Cartesian command interface for poses.
A Cartesian command interface for twists.
TwistCommandHandle()=default
geometry_msgs::Pose getCommand() const
virtual ~PoseCommandHandle()=default
geometry_msgs::Pose * cmd_
geometry_msgs::Twist getCommand() const
A handle for setting twist commands.
TwistCommandHandle(const CartesianStateHandle &state_handle, geometry_msgs::Twist *cmd)
A handle for setting pose commands.
void setCommand(const geometry_msgs::Pose &pose)
void setCommand(const geometry_msgs::Twist &twist)
const geometry_msgs::Pose * getCommandPtr() const
geometry_msgs::Twist * cmd_
PoseCommandHandle()=default
PoseCommandHandle(const CartesianStateHandle &state_handle, geometry_msgs::Pose *cmd)
virtual ~TwistCommandHandle()=default
const geometry_msgs::Twist * getCommandPtr() const