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

#include <command_sender.h>

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

Public Member Functions

 ChassisCommandSender (ros::NodeHandle &nh)
 
void sendChassisCommand (const ros::Time &time, bool is_gyro)
 
void setFollowVelDes (double follow_vel_des)
 
void setZero () override
 
void updateCapacityData (const rm_msgs::PowerManagementSampleAndStatusData data) override
 
void updateGameRobotStatus (const rm_msgs::GameRobotStatus data) override
 
void updatePowerHeatData (const rm_msgs::PowerHeatData data) override
 
void updateRefereeStatus (bool status)
 
void updateSafetyPower (int safety_power)
 
- Public Member Functions inherited from rm_common::TimeStampCommandSenderBase< rm_msgs::ChassisCmd >
void sendCommand (const ros::Time &time) override
 
 TimeStampCommandSenderBase (ros::NodeHandle &nh)
 
- Public Member Functions inherited from rm_common::CommandSenderBase< rm_msgs::ChassisCmd >
 CommandSenderBase (ros::NodeHandle &nh)
 
rm_msgs::ChassisCmd * getMsg ()
 
void setMode (int mode)
 
virtual void updateGameStatus (const rm_msgs::GameStatus data)
 

Public Attributes

PowerLimitpower_limit_
 

Private Attributes

LinearInterp accel_x_
 
LinearInterp accel_y_
 
LinearInterp accel_z_
 

Additional Inherited Members

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

Detailed Description

Definition at line 258 of file command_sender.h.

Constructor & Destructor Documentation

◆ ChassisCommandSender()

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

Definition at line 261 of file command_sender.h.

Member Function Documentation

◆ sendChassisCommand()

void rm_common::ChassisCommandSender::sendChassisCommand ( const ros::Time time,
bool  is_gyro 
)
inline

Definition at line 303 of file command_sender.h.

◆ setFollowVelDes()

void rm_common::ChassisCommandSender::setFollowVelDes ( double  follow_vel_des)
inline

Definition at line 299 of file command_sender.h.

◆ setZero()

void rm_common::ChassisCommandSender::setZero ( )
inlineoverridevirtual

◆ updateCapacityData()

void rm_common::ChassisCommandSender::updateCapacityData ( const rm_msgs::PowerManagementSampleAndStatusData  data)
inlineoverridevirtual

Reimplemented from rm_common::CommandSenderBase< rm_msgs::ChassisCmd >.

Definition at line 291 of file command_sender.h.

◆ updateGameRobotStatus()

void rm_common::ChassisCommandSender::updateGameRobotStatus ( const rm_msgs::GameRobotStatus  data)
inlineoverridevirtual

Reimplemented from rm_common::CommandSenderBase< rm_msgs::ChassisCmd >.

Definition at line 283 of file command_sender.h.

◆ updatePowerHeatData()

void rm_common::ChassisCommandSender::updatePowerHeatData ( const rm_msgs::PowerHeatData  data)
inlineoverridevirtual

Reimplemented from rm_common::CommandSenderBase< rm_msgs::ChassisCmd >.

Definition at line 287 of file command_sender.h.

◆ updateRefereeStatus()

void rm_common::ChassisCommandSender::updateRefereeStatus ( bool  status)
inline

Definition at line 295 of file command_sender.h.

◆ updateSafetyPower()

void rm_common::ChassisCommandSender::updateSafetyPower ( int  safety_power)
inline

Definition at line 279 of file command_sender.h.

Member Data Documentation

◆ accel_x_

LinearInterp rm_common::ChassisCommandSender::accel_x_
private

Definition at line 315 of file command_sender.h.

◆ accel_y_

LinearInterp rm_common::ChassisCommandSender::accel_y_
private

Definition at line 315 of file command_sender.h.

◆ accel_z_

LinearInterp rm_common::ChassisCommandSender::accel_z_
private

Definition at line 315 of file command_sender.h.

◆ power_limit_

PowerLimit* rm_common::ChassisCommandSender::power_limit_

Definition at line 311 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