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