mirror of https://github.com/ArduPilot/ardupilot
Blimp: stop sending SENSOR_OFFSETS
Only works for first compass instance. We have all of these in parameters anyway.
This commit is contained in:
parent
aa22126355
commit
dbf88265c0
|
@ -299,7 +299,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
|||
MSG_SCALED_PRESSURE,
|
||||
MSG_SCALED_PRESSURE2,
|
||||
MSG_SCALED_PRESSURE3,
|
||||
MSG_SENSOR_OFFSETS
|
||||
};
|
||||
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
MSG_SYS_STATUS,
|
||||
|
@ -664,4 +663,4 @@ uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
|
|||
// need to convert -180->180 to 0->360/2
|
||||
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
|
Loading…
Reference in New Issue