AP_Mount: gimbal_manager_set_pitchyaw is not a command

This commit is contained in:
olliw42 2023-11-04 10:03:14 +01:00 committed by Randy Mackay
parent c1831bae32
commit 4ffdb65288
5 changed files with 7 additions and 7 deletions

View File

@ -445,7 +445,7 @@ void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){
}
}
void AP_Mount::handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg)
void AP_Mount::handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg)
{
mavlink_gimbal_manager_set_pitchyaw_t packet;
mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg,&packet);
@ -906,7 +906,7 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m
handle_gimbal_manager_set_attitude(msg);
break;
case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW:
handle_command_gimbal_manager_set_pitchyaw(msg);
handle_gimbal_manager_set_pitchyaw(msg);
break;
case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION:
handle_gimbal_device_information(msg);

View File

@ -296,7 +296,7 @@ private:
MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
void handle_gimbal_manager_set_attitude(const mavlink_message_t &msg);
void handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg);
void handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg);
void handle_global_position_int(const mavlink_message_t &msg);
void handle_gimbal_device_information(const mavlink_message_t &msg);
void handle_gimbal_device_attitude_status(const mavlink_message_t &msg);

View File

@ -106,7 +106,7 @@ void AP_Mount_Backend::clear_roi_target()
_roi_target_set = false;
// reset the mode if in GPS tracking mode
if (_mode == MAV_MOUNT_MODE_GPS_POINT) {
if (get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get();
set_mode(default_mode);
}