|
rm_control
|
#include <command_sender.h>


Public Member Functions | |
| Vel3DCommandSender (ros::NodeHandle &nh) | |
| void | setLinearVel (double scale_x, double scale_y, double scale_z) |
| void | setAngularVel (double scale_x, double scale_y, double scale_z) |
| void | setZero () override |
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) | |
| void | setMode (int mode) |
| virtual void | updateGameRobotStatus (const rm_msgs::GameRobotStatus data) |
| virtual void | updateGameStatus (const rm_msgs::GameStatus data) |
| virtual void | updateCapacityData (const rm_msgs::PowerManagementSampleAndStatusData data) |
| virtual void | updatePowerHeatData (const rm_msgs::PowerHeatData data) |
| geometry_msgs::TwistStamped * | getMsg () |
Additional Inherited Members | |
Protected Attributes inherited from rm_common::CommandSenderBase< geometry_msgs::TwistStamped > | |
| std::string | topic_ |
| uint32_t | queue_size_ |
| ros::Publisher | pub_ |
| geometry_msgs::TwistStamped | msg_ |
|
inlineexplicit |
|
inline |
|
inline |
|
inlineoverridevirtual |