Plane: fixed APM1-1280 build
This commit is contained in:
parent
9824f6c223
commit
635b3fabda
@ -1146,6 +1146,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
if (packet.param4 == 1) {
|
||||
trim_radio();
|
||||
}
|
||||
#if !defined( __AVR_ATmega1280__ )
|
||||
if (packet.param5 == 1) {
|
||||
float trim_roll, trim_pitch;
|
||||
AP_InertialSensor_UserInteract_MAVLink interact(chan);
|
||||
@ -1154,6 +1155,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user