mirror of https://github.com/ArduPilot/ardupilot
Vehicles: handle MSG_NAMED_FLOAT to fix ci failures
This commit is contained in:
parent
2e8d50e8e4
commit
a2360147d1
|
@ -486,6 +486,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||
case MSG_GIMBAL_REPORT:
|
||||
case MSG_RPM:
|
||||
case MSG_POSITION_TARGET_GLOBAL_INT:
|
||||
case MSG_NAMED_FLOAT:
|
||||
break; // just here to prevent a warning
|
||||
}
|
||||
return true;
|
||||
|
|
|
@ -271,6 +271,7 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
|||
case MSG_RPM:
|
||||
case MSG_MISSION_ITEM_REACHED:
|
||||
case MSG_POSITION_TARGET_GLOBAL_INT:
|
||||
case MSG_NAMED_FLOAT:
|
||||
break; // just here to prevent a warning
|
||||
}
|
||||
return true;
|
||||
|
|
|
@ -583,6 +583,8 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
|||
case MSG_BATTERY_STATUS:
|
||||
send_battery_status(copter.battery);
|
||||
break;
|
||||
case MSG_NAMED_FLOAT:
|
||||
break;
|
||||
}
|
||||
|
||||
return true;
|
||||
|
|
|
@ -687,6 +687,8 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
|||
case MSG_BATTERY_STATUS:
|
||||
send_battery_status(plane.battery);
|
||||
break;
|
||||
case MSG_NAMED_FLOAT:
|
||||
break;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue