APM: allow RawSensors stream rate to be saved if <= 5

this makes it possible to configure all stream rates via a parameter
file
This commit is contained in:
Andrew Tridgell 2012-09-21 07:54:21 +10:00
parent 04111ebcdf
commit 060b7dd5d4
1 changed files with 8 additions and 6 deletions

View File

@ -968,9 +968,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_DATA_STREAM_RAW_SENSORS:
streamRateRawSensors = freq; // We do not set and save this one so that if HIL is shut down incorrectly
// we will not continue to broadcast raw sensor data at 50Hz.
if (freq <= 5) {
streamRateRawSensors.set_and_save_ifchanged(freq);
} else {
// We do not set and save this one so that if HIL is shut down incorrectly
// we will not continue to broadcast raw sensor data at 50Hz.
streamRateRawSensors = freq;
}
break;
case MAV_DATA_STREAM_EXTENDED_STATUS:
streamRateExtendedStatus.set_and_save_ifchanged(freq);
break;
@ -983,10 +989,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
streamRateRawController.set_and_save_ifchanged(freq);
break;
//case MAV_DATA_STREAM_RAW_SENSOR_FUSION:
// streamRateRawSensorFusion.set_and_save(freq);
// break;
case MAV_DATA_STREAM_POSITION:
streamRatePosition.set_and_save_ifchanged(freq);
break;