mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: correct indentation and style on GCS_Mavlink
Remove trailling whitespace, tabs, limit single line if-statement scope, add missing space
This commit is contained in:
parent
326e0f224f
commit
5ed9d22bf6
@ -485,8 +485,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||||||
break; // just here to prevent a warning
|
break; // just here to prevent a warning
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -595,7 +593,9 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (rover.in_mavlink_delay) {
|
if (rover.in_mavlink_delay) {
|
||||||
#if HIL_MODE != HIL_MODE_DISABLED
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
@ -613,14 +613,18 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
||||||
send_message(MSG_RAW_IMU1);
|
send_message(MSG_RAW_IMU1);
|
||||||
send_message(MSG_RAW_IMU3);
|
send_message(MSG_RAW_IMU3);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
|
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
|
||||||
send_message(MSG_EXTENDED_STATUS1);
|
send_message(MSG_EXTENDED_STATUS1);
|
||||||
@ -630,7 +634,9 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||||||
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_POSITION)) {
|
if (stream_trigger(STREAM_POSITION)) {
|
||||||
// sent with GPS read
|
// sent with GPS read
|
||||||
@ -638,20 +644,26 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||||||
send_message(MSG_LOCAL_POSITION);
|
send_message(MSG_LOCAL_POSITION);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
||||||
send_message(MSG_SERVO_OUT);
|
send_message(MSG_SERVO_OUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
||||||
send_message(MSG_RADIO_OUT);
|
send_message(MSG_RADIO_OUT);
|
||||||
send_message(MSG_RADIO_IN);
|
send_message(MSG_RADIO_IN);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_EXTRA1)) {
|
if (stream_trigger(STREAM_EXTRA1)) {
|
||||||
send_message(MSG_ATTITUDE);
|
send_message(MSG_ATTITUDE);
|
||||||
@ -661,13 +673,17 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_EXTRA2)) {
|
if (stream_trigger(STREAM_EXTRA2)) {
|
||||||
send_message(MSG_VFR_HUD);
|
send_message(MSG_VFR_HUD);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rover.gcs_out_of_time) return;
|
if (rover.gcs_out_of_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (stream_trigger(STREAM_EXTRA3)) {
|
if (stream_trigger(STREAM_EXTRA3)) {
|
||||||
send_message(MSG_AHRS);
|
send_message(MSG_AHRS);
|
||||||
@ -906,8 +922,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
} else {
|
} else {
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
send_text(MAV_SEVERITY_WARNING, "Unsupported preflight calibration");
|
send_text(MAV_SEVERITY_WARNING, "Unsupported preflight calibration");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -1196,7 +1211,10 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
// allow override of RC channel values for HIL
|
// allow override of RC channel values for HIL
|
||||||
// or for complete GCS control of switch position
|
// or for complete GCS control of switch position
|
||||||
// and RC PWM values.
|
// and RC PWM values.
|
||||||
if(msg->sysid != rover.g.sysid_my_gcs) break; // Only accept control from our gcs
|
if (msg->sysid != rover.g.sysid_my_gcs) { // Only accept control from our gcs
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
mavlink_rc_channels_override_t packet;
|
mavlink_rc_channels_override_t packet;
|
||||||
int16_t v[8];
|
int16_t v[8];
|
||||||
mavlink_msg_rc_channels_override_decode(msg, &packet);
|
mavlink_msg_rc_channels_override_decode(msg, &packet);
|
||||||
@ -1220,7 +1238,10 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||||
{
|
{
|
||||||
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||||
if(msg->sysid != rover.g.sysid_my_gcs) break;
|
if (msg->sysid != rover.g.sysid_my_gcs) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
rover.last_heartbeat_ms = rover.failsafe.rc_override_timer = AP_HAL::millis();
|
rover.last_heartbeat_ms = rover.failsafe.rc_override_timer = AP_HAL::millis();
|
||||||
rover.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
rover.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
||||||
break;
|
break;
|
||||||
@ -1460,7 +1481,9 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
void Rover::mavlink_delay_cb()
|
void Rover::mavlink_delay_cb()
|
||||||
{
|
{
|
||||||
static uint32_t last_1hz, last_50hz, last_5s;
|
static uint32_t last_1hz, last_50hz, last_5s;
|
||||||
if (!gcs[0].initialised || in_mavlink_delay) return;
|
if (!gcs[0].initialised || in_mavlink_delay) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
in_mavlink_delay = true;
|
in_mavlink_delay = true;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user