Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
rm_common::Vel2DCommandSender Class Reference

#include <command_sender.h>

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

Public Member Functions

void set2DVel (double scale_x, double scale_y, double scale_z)
 
void setAngularZVel (double scale)
 
void setAngularZVel (double scale, double limit)
 
void setLinearXVel (double scale)
 
void setLinearYVel (double scale)
 
void setZero () override
 
void updateTrackData (const rm_msgs::TrackData &data)
 
 Vel2DCommandSender (ros::NodeHandle &nh)
 
- Public Member Functions inherited from rm_common::CommandSenderBase< geometry_msgs::Twist >
 CommandSenderBase (ros::NodeHandle &nh)
 
geometry_msgs::Twist * 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)
 

Protected Member Functions

void chassisCmdCallback (const rm_msgs::ChassisCmd::ConstPtr &msg)
 

Protected Attributes

ros::Subscriber chassis_power_limit_subscriber_
 
LinearInterp max_angular_z_
 
LinearInterp max_linear_x_
 
LinearInterp max_linear_y_
 
double power_limit_ = 0.
 
double target_vel_yaw_threshold_ {}
 
rm_msgs::TrackData track_data_
 
double vel_direction_ = 1.
 
- Protected Attributes inherited from rm_common::CommandSenderBase< geometry_msgs::Twist >
geometry_msgs::Twist msg_
 
ros::Publisher pub_
 
uint32_t queue_size_
 
std::string topic_
 

Detailed Description

Definition at line 177 of file command_sender.h.

Constructor & Destructor Documentation

◆ Vel2DCommandSender()

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

Definition at line 180 of file command_sender.h.

Member Function Documentation

◆ chassisCmdCallback()

void rm_common::Vel2DCommandSender::chassisCmdCallback ( const rm_msgs::ChassisCmd::ConstPtr &  msg)
inlineprotected

Definition at line 245 of file command_sender.h.

◆ set2DVel()

void rm_common::Vel2DCommandSender::set2DVel ( double  scale_x,
double  scale_y,
double  scale_z 
)
inline

Definition at line 231 of file command_sender.h.

◆ setAngularZVel() [1/2]

void rm_common::Vel2DCommandSender::setAngularZVel ( double  scale)
inline

Definition at line 214 of file command_sender.h.

◆ setAngularZVel() [2/2]

void rm_common::Vel2DCommandSender::setAngularZVel ( double  scale,
double  limit 
)
inline

Definition at line 222 of file command_sender.h.

◆ setLinearXVel()

void rm_common::Vel2DCommandSender::setLinearXVel ( double  scale)
inline

Definition at line 206 of file command_sender.h.

◆ setLinearYVel()

void rm_common::Vel2DCommandSender::setLinearYVel ( double  scale)
inline

Definition at line 210 of file command_sender.h.

◆ setZero()

void rm_common::Vel2DCommandSender::setZero ( )
inlineoverridevirtual

◆ updateTrackData()

void rm_common::Vel2DCommandSender::updateTrackData ( const rm_msgs::TrackData &  data)
inline

Definition at line 202 of file command_sender.h.

Member Data Documentation

◆ chassis_power_limit_subscriber_

ros::Subscriber rm_common::Vel2DCommandSender::chassis_power_limit_subscriber_
protected

Definition at line 254 of file command_sender.h.

◆ max_angular_z_

LinearInterp rm_common::Vel2DCommandSender::max_angular_z_
protected

Definition at line 250 of file command_sender.h.

◆ max_linear_x_

LinearInterp rm_common::Vel2DCommandSender::max_linear_x_
protected

Definition at line 250 of file command_sender.h.

◆ max_linear_y_

LinearInterp rm_common::Vel2DCommandSender::max_linear_y_
protected

Definition at line 250 of file command_sender.h.

◆ power_limit_

double rm_common::Vel2DCommandSender::power_limit_ = 0.
protected

Definition at line 251 of file command_sender.h.

◆ target_vel_yaw_threshold_

double rm_common::Vel2DCommandSender::target_vel_yaw_threshold_ {}
protected

Definition at line 252 of file command_sender.h.

◆ track_data_

rm_msgs::TrackData rm_common::Vel2DCommandSender::track_data_
protected

Definition at line 255 of file command_sender.h.

◆ vel_direction_

double rm_common::Vel2DCommandSender::vel_direction_ = 1.
protected

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