mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
GCS_MAVLink: remove check for max INS instances
For all supported boards the maximum number of instances is 3.
This commit is contained in:
parent
f99d64e621
commit
ae77c4b692
@ -1059,7 +1059,7 @@ void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &comp
|
|||||||
mag.x,
|
mag.x,
|
||||||
mag.y,
|
mag.y,
|
||||||
mag.z);
|
mag.z);
|
||||||
#if INS_MAX_INSTANCES > 1
|
|
||||||
if (ins.get_gyro_count() <= 1 &&
|
if (ins.get_gyro_count() <= 1 &&
|
||||||
ins.get_accel_count() <= 1 &&
|
ins.get_accel_count() <= 1 &&
|
||||||
compass.get_count() <= 1) {
|
compass.get_count() <= 1) {
|
||||||
@ -1084,8 +1084,7 @@ void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &comp
|
|||||||
mag.x,
|
mag.x,
|
||||||
mag.y,
|
mag.y,
|
||||||
mag.z);
|
mag.z);
|
||||||
#endif
|
|
||||||
#if INS_MAX_INSTANCES > 2
|
|
||||||
if (ins.get_gyro_count() <= 2 &&
|
if (ins.get_gyro_count() <= 2 &&
|
||||||
ins.get_accel_count() <= 2 &&
|
ins.get_accel_count() <= 2 &&
|
||||||
compass.get_count() <= 2) {
|
compass.get_count() <= 2) {
|
||||||
@ -1110,7 +1109,6 @@ void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &comp
|
|||||||
mag.x,
|
mag.x,
|
||||||
mag.y,
|
mag.y,
|
||||||
mag.z);
|
mag.z);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
|
void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
|
||||||
|
Loading…
Reference in New Issue
Block a user