mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Mount: clarify yaw_lock comments
This commit is contained in:
parent
4755a60863
commit
d0d33b0b36
@ -249,7 +249,7 @@ void AP_Mount::set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode)
|
|||||||
backend->set_mode(mode);
|
backend->set_mode(mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
// set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
|
// set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
|
||||||
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
|
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
|
||||||
void AP_Mount::set_yaw_lock(uint8_t instance, bool yaw_lock)
|
void AP_Mount::set_yaw_lock(uint8_t instance, bool yaw_lock)
|
||||||
{
|
{
|
||||||
|
@ -151,7 +151,7 @@ public:
|
|||||||
void set_mode_to_default() { set_mode_to_default(_primary); }
|
void set_mode_to_default() { set_mode_to_default(_primary); }
|
||||||
void set_mode_to_default(uint8_t instance);
|
void set_mode_to_default(uint8_t instance);
|
||||||
|
|
||||||
// set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
|
// set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
|
||||||
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
|
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
|
||||||
void set_yaw_lock(bool yaw_lock) { set_yaw_lock(_primary, yaw_lock); }
|
void set_yaw_lock(bool yaw_lock) { set_yaw_lock(_primary, yaw_lock); }
|
||||||
void set_yaw_lock(uint8_t instance, bool yaw_lock);
|
void set_yaw_lock(uint8_t instance, bool yaw_lock);
|
||||||
|
@ -79,7 +79,7 @@ public:
|
|||||||
// set mount's mode
|
// set mount's mode
|
||||||
bool set_mode(enum MAV_MOUNT_MODE mode);
|
bool set_mode(enum MAV_MOUNT_MODE mode);
|
||||||
|
|
||||||
// set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
|
// set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
|
||||||
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
|
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
|
||||||
void set_yaw_lock(bool yaw_lock) { _yaw_lock = yaw_lock; }
|
void set_yaw_lock(bool yaw_lock) { _yaw_lock = yaw_lock; }
|
||||||
|
|
||||||
@ -298,7 +298,7 @@ protected:
|
|||||||
uint8_t _instance; // this instance's number
|
uint8_t _instance; // this instance's number
|
||||||
|
|
||||||
MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum)
|
MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum)
|
||||||
bool _yaw_lock; // True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame
|
bool _yaw_lock; // yaw_lock used in RC_TARGETING mode. True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame
|
||||||
|
|
||||||
// structure for MAVLink Targeting angle and rate targets
|
// structure for MAVLink Targeting angle and rate targets
|
||||||
struct {
|
struct {
|
||||||
|
Loading…
Reference in New Issue
Block a user