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

#include <command_sender.h>

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

Public Member Functions

int getIndex ()
 
 JointPointCommandSender (ros::NodeHandle &nh, const sensor_msgs::JointState &joint_state)
 
void setPoint (double point)
 
void setZero () override
 
- Public Member Functions inherited from rm_common::CommandSenderBase< std_msgs::Float64 >
 CommandSenderBase (ros::NodeHandle &nh)
 
std_msgs::Float64 * 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)
 

Private Attributes

int index_ {}
 
std::string joint_ {}
 
const sensor_msgs::JointState & joint_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 789 of file command_sender.h.

Constructor & Destructor Documentation

◆ JointPointCommandSender()

rm_common::JointPointCommandSender::JointPointCommandSender ( ros::NodeHandle nh,
const sensor_msgs::JointState &  joint_state 
)
inlineexplicit

Definition at line 792 of file command_sender.h.

Member Function Documentation

◆ getIndex()

int rm_common::JointPointCommandSender::getIndex ( )
inline

Definition at line 801 of file command_sender.h.

◆ setPoint()

void rm_common::JointPointCommandSender::setPoint ( double  point)
inline

Definition at line 797 of file command_sender.h.

◆ setZero()

void rm_common::JointPointCommandSender::setZero ( )
inlineoverridevirtual

Member Data Documentation

◆ index_

int rm_common::JointPointCommandSender::index_ {}
private

Definition at line 819 of file command_sender.h.

◆ joint_

std::string rm_common::JointPointCommandSender::joint_ {}
private

Definition at line 818 of file command_sender.h.

◆ joint_state_

const sensor_msgs::JointState& rm_common::JointPointCommandSender::joint_state_
private

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