AP_Mount: Siyi set_motion_mode() now returns bool

And the mode param is now const.
This commit is contained in:
Nick Exton 2023-09-07 10:12:42 +10:00 committed by Randy Mackay
parent 9fe5f4151e
commit 62858ff91f
2 changed files with 5 additions and 3 deletions

View File

@ -618,7 +618,8 @@ void AP_Mount_Siyi::rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool y
// FOLLOW: roll and pitch are in earth-frame, yaw is in body-frame
// LOCK: roll, pitch and yaw are all in earth-frame
// FPV: roll, pitch and yaw are all in body-frame
void AP_Mount_Siyi::set_motion_mode(GimbalMotionMode mode)
// Returns true if mode successfully sent to Gimbal
bool AP_Mount_Siyi::set_motion_mode(const GimbalMotionMode mode)
{
PhotoFunction data = PhotoFunction::LOCK_MODE;
switch (mode) {
@ -626,7 +627,7 @@ void AP_Mount_Siyi::set_motion_mode(GimbalMotionMode mode)
case GimbalMotionMode::FOLLOW: data = PhotoFunction::FOLLOW_MODE; break;
case GimbalMotionMode::FPV: data = PhotoFunction::FPV_MODE; break;
}
send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)data);
return send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)data);
}
// send target pitch and yaw rates to gimbal

View File

@ -251,7 +251,8 @@ private:
// FOLLOW: roll and pitch are in earth-frame, yaw is in body-frame
// LOCK: roll, pitch and yaw are all in earth-frame
// FPV: roll, pitch and yaw are all in body-frame
void set_motion_mode(GimbalMotionMode mode);
// Returns true if message successfully sent to Gimbal
bool set_motion_mode(const GimbalMotionMode mode);
// send target pitch and yaw rates to gimbal
// yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame