#include <command_sender.h>

Public Member Functions | |
| void | setAngularVel (double scale_x, double scale_y, double scale_z) |
| void | setLinearVel (double scale_x, double scale_y, double scale_z) |
| void | setZero () override |
| Vel3DCommandSender (ros::NodeHandle &nh) | |
Public Member Functions inherited from rm_common::HeaderStampCommandSenderBase< geometry_msgs::TwistStamped > | |
| HeaderStampCommandSenderBase (ros::NodeHandle &nh) | |
| void | sendCommand (const ros::Time &time) override |
Public Member Functions inherited from rm_common::CommandSenderBase< geometry_msgs::TwistStamped > | |
| CommandSenderBase (ros::NodeHandle &nh) | |
| geometry_msgs::TwistStamped * | getMsg () |
| void | setMode (int mode) |
| virtual void | updateCapacityData (const rm_msgs::PowerManagementSampleAndStatusData data) |
| virtual void | updateGameRobotStatus (const rm_msgs::GameRobotStatus data) |
| virtual void | updateGameStatus (const rm_msgs::GameStatus data) |
| virtual void | updatePowerHeatData (const rm_msgs::PowerHeatData data) |
Private Attributes | |
| double | max_angular_x_ {} |
| double | max_angular_y_ {} |
| double | max_angular_z_ {} |
| double | max_linear_x_ {} |
| double | max_linear_y_ {} |
| double | max_linear_z_ {} |
Additional Inherited Members | |
Protected Attributes inherited from rm_common::CommandSenderBase< geometry_msgs::TwistStamped > | |
| geometry_msgs::TwistStamped | msg_ |
| ros::Publisher | pub_ |
| uint32_t | queue_size_ |
| std::string | topic_ |
Definition at line 668 of file command_sender.h.
|
inlineexplicit |
Definition at line 671 of file command_sender.h.
|
inline |
Definition at line 692 of file command_sender.h.
|
inline |
Definition at line 686 of file command_sender.h.
|
inlineoverridevirtual |
Implements rm_common::CommandSenderBase< geometry_msgs::TwistStamped >.
Definition at line 698 of file command_sender.h.
|
private |
Definition at line 709 of file command_sender.h.
|
private |
Definition at line 709 of file command_sender.h.
|
private |
Definition at line 709 of file command_sender.h.
|
private |
Definition at line 709 of file command_sender.h.
|
private |
Definition at line 709 of file command_sender.h.
|
private |
Definition at line 709 of file command_sender.h.