#include <command_sender.h>
Public Member Functions | |
CommandSenderBase (ros::NodeHandle &nh) | |
MsgType * | getMsg () |
virtual void | sendCommand (const ros::Time &time) |
void | setMode (int mode) |
virtual void | setZero ()=0 |
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) |
Protected Attributes | |
MsgType | msg_ |
ros::Publisher | pub_ |
uint32_t | queue_size_ |
std::string | topic_ |
Definition at line 105 of file command_sender.h.
|
inlineexplicit |
Definition at line 139 of file command_sender.h.
|
inline |
Definition at line 168 of file command_sender.h.
|
inlinevirtual |
Reimplemented in rm_common::CameraSwitchCommandSender, rm_common::CardCommandSender, rm_common::JointPositionBinaryCommandSender, rm_common::ShooterCommandSender, rm_common::HeaderStampCommandSenderBase< MsgType >, rm_common::HeaderStampCommandSenderBase< geometry_msgs::TwistStamped >, rm_common::TimeStampCommandSenderBase< MsgType >, rm_common::TimeStampCommandSenderBase< rm_msgs::GimbalCmd >, rm_common::TimeStampCommandSenderBase< rm_msgs::ShootCmd >, rm_common::TimeStampCommandSenderBase< rm_msgs::ChassisCmd >, and rm_common::TimeStampCommandSenderBase< rm_msgs::MultiDofCmd >.
Definition at line 151 of file command_sender.h.
|
inline |
Definition at line 146 of file command_sender.h.
|
pure virtual |
Implemented in rm_common::MultiDofCommandSender, rm_common::CameraSwitchCommandSender, rm_common::JointPointCommandSender, rm_common::CardCommandSender, rm_common::JointPositionBinaryCommandSender, rm_common::Vel3DCommandSender, rm_common::LegCommandSender, rm_common::BalanceCommandSender, rm_common::ShooterCommandSender, rm_common::GimbalCommandSender, rm_common::ChassisCommandSender, and rm_common::Vel2DCommandSender.
|
inlinevirtual |
Reimplemented in rm_common::ChassisCommandSender.
Definition at line 161 of file command_sender.h.
|
inlinevirtual |
Reimplemented in rm_common::ShooterCommandSender, and rm_common::ChassisCommandSender.
Definition at line 155 of file command_sender.h.
|
inlinevirtual |
Definition at line 158 of file command_sender.h.
|
inlinevirtual |
Reimplemented in rm_common::ShooterCommandSender, and rm_common::ChassisCommandSender.
Definition at line 164 of file command_sender.h.
|
protected |
Definition at line 177 of file command_sender.h.
|
protected |
Definition at line 176 of file command_sender.h.
|
protected |
Definition at line 175 of file command_sender.h.
|
protected |
Definition at line 174 of file command_sender.h.