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

#include <command_sender.h>

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

Public Member Functions

void setAngularVel (double scale_x, double scale_y, double scale_z)
 
void setLinearVel (double scale_x, double scale_y, double scale_z)
 
void setZero () override
 
 Vel3DCommandSender (ros::NodeHandle &nh)
 
- Public Member Functions inherited from rm_common::HeaderStampCommandSenderBase< geometry_msgs::TwistStamped >
 HeaderStampCommandSenderBase (ros::NodeHandle &nh)
 
void sendCommand (const ros::Time &time) override
 
- Public Member Functions inherited from rm_common::CommandSenderBase< geometry_msgs::TwistStamped >
 CommandSenderBase (ros::NodeHandle &nh)
 
geometry_msgs::TwistStamped * 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 max_angular_x_ {}
 
double max_angular_y_ {}
 
double max_angular_z_ {}
 
double max_linear_x_ {}
 
double max_linear_y_ {}
 
double max_linear_z_ {}
 

Additional Inherited Members

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

Detailed Description

Definition at line 625 of file command_sender.h.

Constructor & Destructor Documentation

◆ Vel3DCommandSender()

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

Definition at line 628 of file command_sender.h.

Member Function Documentation

◆ setAngularVel()

void rm_common::Vel3DCommandSender::setAngularVel ( double  scale_x,
double  scale_y,
double  scale_z 
)
inline

Definition at line 649 of file command_sender.h.

◆ setLinearVel()

void rm_common::Vel3DCommandSender::setLinearVel ( double  scale_x,
double  scale_y,
double  scale_z 
)
inline

Definition at line 643 of file command_sender.h.

◆ setZero()

void rm_common::Vel3DCommandSender::setZero ( )
inlineoverridevirtual

Member Data Documentation

◆ max_angular_x_

double rm_common::Vel3DCommandSender::max_angular_x_ {}
private

Definition at line 666 of file command_sender.h.

◆ max_angular_y_

double rm_common::Vel3DCommandSender::max_angular_y_ {}
private

Definition at line 666 of file command_sender.h.

◆ max_angular_z_

double rm_common::Vel3DCommandSender::max_angular_z_ {}
private

Definition at line 666 of file command_sender.h.

◆ max_linear_x_

double rm_common::Vel3DCommandSender::max_linear_x_ {}
private

Definition at line 666 of file command_sender.h.

◆ max_linear_y_

double rm_common::Vel3DCommandSender::max_linear_y_ {}
private

Definition at line 666 of file command_sender.h.

◆ max_linear_z_

double rm_common::Vel3DCommandSender::max_linear_z_ {}
private

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