rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
rm_common::GimbalCommandSender Class Reference

#include <command_sender.h>

Inheritance diagram for rm_common::GimbalCommandSender:
Collaboration diagram for rm_common::GimbalCommandSender:

Public Member Functions

 GimbalCommandSender (ros::NodeHandle &nh)
 
 ~GimbalCommandSender ()=default
 
void setRate (double scale_yaw, double scale_pitch)
 
void setGimbalTraj (double traj_yaw, double traj_pitch)
 
void setGimbalTrajFrameId (std::string traj_frame_id)
 
void setZero () override
 
void setBulletSpeed (double bullet_speed)
 
void setEject (bool flag)
 
void setUseRc (bool flag)
 
bool getEject () const
 
void setPoint (geometry_msgs::PointStamped point)
 
- Public Member Functions inherited from rm_common::TimeStampCommandSenderBase< rm_msgs::GimbalCmd >
 TimeStampCommandSenderBase (ros::NodeHandle &nh)
 
void sendCommand (const ros::Time &time) override
 
- Public Member Functions inherited from rm_common::CommandSenderBase< rm_msgs::GimbalCmd >
 CommandSenderBase (ros::NodeHandle &nh)
 
void setMode (int mode)
 
virtual void updateGameRobotStatus (const rm_msgs::GameRobotStatus data)
 
virtual void updateGameStatus (const rm_msgs::GameStatus data)
 
virtual void updateCapacityData (const rm_msgs::PowerManagementSampleAndStatusData data)
 
virtual void updatePowerHeatData (const rm_msgs::PowerHeatData data)
 
rm_msgs::GimbalCmd * getMsg ()
 

Additional Inherited Members

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

Constructor & Destructor Documentation

◆ GimbalCommandSender()

rm_common::GimbalCommandSender::GimbalCommandSender ( ros::NodeHandle & nh)
inlineexplicit

◆ ~GimbalCommandSender()

rm_common::GimbalCommandSender::~GimbalCommandSender ( )
default

Member Function Documentation

◆ getEject()

bool rm_common::GimbalCommandSender::getEject ( ) const
inline

◆ setBulletSpeed()

void rm_common::GimbalCommandSender::setBulletSpeed ( double bullet_speed)
inline

◆ setEject()

void rm_common::GimbalCommandSender::setEject ( bool flag)
inline

◆ setGimbalTraj()

void rm_common::GimbalCommandSender::setGimbalTraj ( double traj_yaw,
double traj_pitch )
inline

◆ setGimbalTrajFrameId()

void rm_common::GimbalCommandSender::setGimbalTrajFrameId ( std::string traj_frame_id)
inline

◆ setPoint()

void rm_common::GimbalCommandSender::setPoint ( geometry_msgs::PointStamped point)
inline

◆ setRate()

void rm_common::GimbalCommandSender::setRate ( double scale_yaw,
double scale_pitch )
inline

◆ setUseRc()

void rm_common::GimbalCommandSender::setUseRc ( bool flag)
inline

◆ setZero()

void rm_common::GimbalCommandSender::setZero ( )
inlineoverridevirtual

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