#include <command_sender.h>
Definition at line 318 of file command_sender.h.
◆ GimbalCommandSender()
rm_common::GimbalCommandSender::GimbalCommandSender |
( |
ros::NodeHandle & |
nh | ) |
|
|
inlineexplicit |
◆ ~GimbalCommandSender()
rm_common::GimbalCommandSender::~GimbalCommandSender |
( |
| ) |
|
|
default |
◆ 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 |
( |
const 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 |
◆ eject_flag_
bool rm_common::GimbalCommandSender::eject_flag_ {} |
|
private |
◆ eject_sensitivity_
double rm_common::GimbalCommandSender::eject_sensitivity_ = 1. |
|
private |
◆ max_pitch_vel_
double rm_common::GimbalCommandSender::max_pitch_vel_ {} |
|
private |
◆ max_yaw_vel_
double rm_common::GimbalCommandSender::max_yaw_vel_ {} |
|
private |
◆ time_constant_pc_
double rm_common::GimbalCommandSender::time_constant_pc_ {} |
|
private |
◆ time_constant_rc_
double rm_common::GimbalCommandSender::time_constant_rc_ {} |
|
private |
◆ track_timeout_
double rm_common::GimbalCommandSender::track_timeout_ {} |
|
private |
◆ use_rc_
bool rm_common::GimbalCommandSender::use_rc_ {} |
|
private |
The documentation for this class was generated from the following file: