mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use SourceSetSelection enum class
This commit is contained in:
parent
29b9157a20
commit
a7f9abcff9
|
@ -4817,7 +4817,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_
|
|||
uint32_t source_set = uint32_t(packet.param1);
|
||||
if ((source_set >= 1) && (source_set <= 3)) {
|
||||
// mavlink command uses range 1 to 3 while ahrs interface accepts 0 to 2
|
||||
AP::ahrs().set_posvelyaw_source_set(source_set-1);
|
||||
AP::ahrs().set_posvelyaw_source_set((AP_NavEKF_Source::SourceSetSelection)(source_set-1));
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_DENIED;
|
||||
|
|
Loading…
Reference in New Issue