#include <command_sender.h>

Public Member Functions | |
| bool | getJump () |
| double | getLgeLength () |
| LegCommandSender (ros::NodeHandle &nh) | |
| void | setJump (bool jump) |
| void | setLgeLength (double length) |
| void | setZero () override |
Public Member Functions inherited from rm_common::CommandSenderBase< rm_msgs::LegCmd > | |
| CommandSenderBase (ros::NodeHandle &nh) | |
| rm_msgs::LegCmd * | getMsg () |
| virtual void | sendCommand (const ros::Time &time) |
| 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) |
Additional Inherited Members | |
Protected Attributes inherited from rm_common::CommandSenderBase< rm_msgs::LegCmd > | |
| rm_msgs::LegCmd | msg_ |
| ros::Publisher | pub_ |
| uint32_t | queue_size_ |
| std::string | topic_ |
Definition at line 642 of file command_sender.h.
|
inlineexplicit |
Definition at line 645 of file command_sender.h.
|
inline |
Definition at line 657 of file command_sender.h.
|
inline |
Definition at line 661 of file command_sender.h.
|
inline |
Definition at line 649 of file command_sender.h.
|
inline |
Definition at line 653 of file command_sender.h.
|
inlineoverridevirtual |
Implements rm_common::CommandSenderBase< rm_msgs::LegCmd >.
Definition at line 665 of file command_sender.h.