Public Member Functions | Private Attributes | List of all members
rm_common::CardCommandSender Class Reference

#include <command_sender.h>

Inheritance diagram for rm_common::CardCommandSender:
Inheritance graph
[legend]

Public Member Functions

 CardCommandSender (ros::NodeHandle &nh)
 
bool getState () const
 
void long_on ()
 
void off ()
 
void sendCommand (const ros::Time &time) override
 
void setZero () override
 
void short_on ()
 
- Public Member Functions inherited from rm_common::CommandSenderBase< std_msgs::Float64 >
 CommandSenderBase (ros::NodeHandle &nh)
 
std_msgs::Float64 * 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 long_pos_ {}
 
double off_pos_ {}
 
double short_pos_ {}
 
bool state {}
 

Additional Inherited Members

- Protected Attributes inherited from rm_common::CommandSenderBase< std_msgs::Float64 >
std_msgs::Float64 msg_
 
ros::Publisher pub_
 
uint32_t queue_size_
 
std::string topic_
 

Detailed Description

Definition at line 707 of file command_sender.h.

Constructor & Destructor Documentation

◆ CardCommandSender()

rm_common::CardCommandSender::CardCommandSender ( ros::NodeHandle nh)
inlineexplicit

Definition at line 710 of file command_sender.h.

Member Function Documentation

◆ getState()

bool rm_common::CardCommandSender::getState ( ) const
inline

Definition at line 730 of file command_sender.h.

◆ long_on()

void rm_common::CardCommandSender::long_on ( )
inline

Definition at line 715 of file command_sender.h.

◆ off()

void rm_common::CardCommandSender::off ( )
inline

Definition at line 725 of file command_sender.h.

◆ sendCommand()

void rm_common::CardCommandSender::sendCommand ( const ros::Time time)
inlineoverridevirtual

Reimplemented from rm_common::CommandSenderBase< std_msgs::Float64 >.

Definition at line 734 of file command_sender.h.

◆ setZero()

void rm_common::CardCommandSender::setZero ( )
inlineoverridevirtual

◆ short_on()

void rm_common::CardCommandSender::short_on ( )
inline

Definition at line 720 of file command_sender.h.

Member Data Documentation

◆ long_pos_

double rm_common::CardCommandSender::long_pos_ {}
private

Definition at line 742 of file command_sender.h.

◆ off_pos_

double rm_common::CardCommandSender::off_pos_ {}
private

Definition at line 742 of file command_sender.h.

◆ short_pos_

double rm_common::CardCommandSender::short_pos_ {}
private

Definition at line 742 of file command_sender.h.

◆ state

bool rm_common::CardCommandSender::state {}
private

Definition at line 741 of file command_sender.h.


The documentation for this class was generated from the following file:


rm_common
Author(s):
autogenerated on Thu Apr 3 2025 02:22:31