mirror of https://github.com/ArduPilot/ardupilot
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
|
@ -43,7 +43,7 @@ void Rover::send_heartbeat(mavlink_channel_t chan)
|
|||
break;
|
||||
}
|
||||
|
||||
#if defined(ENABLE_STICK_MIXING) && (ENABLE_STICK_MIXING==ENABLED)
|
||||
#if defined(ENABLE_STICK_MIXING) && (ENABLE_STICK_MIXING == ENABLED)
|
||||
if (control_mode != INITIALISING) {
|
||||
// all modes except INITIALISING have some form of manual
|
||||
// override if stick mixing is enabled
|
||||
|
@ -485,8 +485,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||
break; // just here to prevent a warning
|
||||
|
||||
}
|
||||
|
||||
|
||||
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 HIL_MODE != HIL_MODE_DISABLED
|
||||
|
@ -613,14 +613,18 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||
return;
|
||||
}
|
||||
|
||||
if (rover.gcs_out_of_time) return;
|
||||
if (rover.gcs_out_of_time) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
||||
send_message(MSG_RAW_IMU1);
|
||||
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)) {
|
||||
send_message(MSG_EXTENDED_STATUS1);
|
||||
|
@ -630,7 +634,9 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||
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)) {
|
||||
// sent with GPS read
|
||||
|
@ -638,20 +644,26 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
|||
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)) {
|
||||
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)) {
|
||||
send_message(MSG_RADIO_OUT);
|
||||
send_message(MSG_RADIO_IN);
|
||||
}
|
||||
|
||||
if (rover.gcs_out_of_time) return;
|
||||
if (rover.gcs_out_of_time) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_EXTRA1)) {
|
||||
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)) {
|
||||
send_message(MSG_VFR_HUD);
|
||||
}
|
||||
|
||||
if (rover.gcs_out_of_time) return;
|
||||
if (rover.gcs_out_of_time) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_EXTRA3)) {
|
||||
send_message(MSG_AHRS);
|
||||
|
@ -725,7 +741,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
mavlink_statustext_t packet;
|
||||
mavlink_msg_statustext_decode(msg, &packet);
|
||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+4] = { 'G','C','S',':'};
|
||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+4] = { 'G', 'C', 'S', ':'};
|
||||
memcpy(&text[4], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
|
||||
rover.DataFlash.Log_Write_Message(text);
|
||||
break;
|
||||
|
@ -737,7 +753,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
mavlink_msg_command_int_decode(msg, &packet);
|
||||
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
||||
|
||||
switch(packet.command) {
|
||||
switch (packet.command) {
|
||||
#if MOUNT == ENABLED
|
||||
case MAV_CMD_DO_SET_ROI: {
|
||||
// param1 : /* Region of interest mode (not used)*/
|
||||
|
@ -789,7 +805,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
// do command
|
||||
|
||||
switch(packet.command) {
|
||||
switch (packet.command) {
|
||||
|
||||
case MAV_CMD_START_RX_PAIR:
|
||||
result = handle_rc_bind(packet);
|
||||
|
@ -863,11 +879,11 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
if(hal.util->get_soft_armed()) {
|
||||
if (hal.util->get_soft_armed()) {
|
||||
result = MAV_RESULT_FAILED;
|
||||
break;
|
||||
}
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
if (is_equal(packet.param1, 1.0f)) {
|
||||
rover.ins.init_gyro();
|
||||
if (rover.ins.gyro_calibrated_ok_all()) {
|
||||
rover.ahrs.reset_gyro_drift();
|
||||
|
@ -875,13 +891,13 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
} else {
|
||||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
} else if (is_equal(packet.param3,1.0f)) {
|
||||
} else if (is_equal(packet.param3, 1.0f)) {
|
||||
rover.init_barometer(false);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else if (is_equal(packet.param4,1.0f)) {
|
||||
} else if (is_equal(packet.param4, 1.0f)) {
|
||||
rover.trim_radio();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else if (is_equal(packet.param5,1.0f)) {
|
||||
} else if (is_equal(packet.param5, 1.0f)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
// start with gyro calibration
|
||||
rover.ins.init_gyro();
|
||||
|
@ -894,20 +910,19 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
rover.ins.acal_init();
|
||||
rover.ins.get_acal()->start(this);
|
||||
|
||||
} else if (is_equal(packet.param5,2.0f)) {
|
||||
} else if (is_equal(packet.param5, 2.0f)) {
|
||||
// start with gyro calibration
|
||||
rover.ins.init_gyro();
|
||||
// accel trim
|
||||
float trim_roll, trim_pitch;
|
||||
if(rover.ins.calibrate_trim(trim_roll, trim_pitch)) {
|
||||
if (rover.ins.calibrate_trim(trim_roll, trim_pitch)) {
|
||||
// reset ahrs's trim to suggested values from calibration routine
|
||||
rover.ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
send_text(MAV_SEVERITY_WARNING, "Unsupported preflight calibration");
|
||||
}
|
||||
break;
|
||||
|
@ -979,15 +994,15 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
||||
if (is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f)) {
|
||||
// when packet.param1 == 3 we reboot to hold in bootloader
|
||||
hal.scheduler->reboot(is_equal(packet.param1,3.0f));
|
||||
hal.scheduler->reboot(is_equal(packet.param1, 3.0f));
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
if (is_equal(packet.param1, 1.0f)) {
|
||||
// run pre_arm_checks and arm_checks and display failures
|
||||
if (rover.arm_motors(AP_Arming::MAVLINK)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
|
@ -1015,7 +1030,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
|
||||
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
if (is_equal(packet.param1, 1.0f)) {
|
||||
send_autopilot_version(FIRMWARE_VERSION);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
@ -1029,7 +1044,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
// param6 : longitude
|
||||
// param7 : altitude
|
||||
result = MAV_RESULT_FAILED; // assume failure
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
if (is_equal(packet.param1, 1.0f)) {
|
||||
rover.init_home();
|
||||
} else {
|
||||
if (is_zero(packet.param5) && is_zero(packet.param6) && is_zero(packet.param7)) {
|
||||
|
@ -1050,9 +1065,9 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
rover.gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
|
||||
(double)(new_home_loc.lat*1.0e-7f),
|
||||
(double)(new_home_loc.lng*1.0e-7f),
|
||||
(uint32_t)(new_home_loc.alt*0.01f));
|
||||
(double)(new_home_loc.lat * 1.0e-7f),
|
||||
(double)(new_home_loc.lng * 1.0e-7f),
|
||||
(uint32_t)(new_home_loc.alt * 0.01f));
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -1196,7 +1211,10 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
// allow override of RC channel values for HIL
|
||||
// or for complete GCS control of switch position
|
||||
// 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;
|
||||
int16_t v[8];
|
||||
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:
|
||||
{
|
||||
// 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.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
||||
break;
|
||||
|
@ -1360,13 +1381,13 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
#endif // HIL_MODE
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
// deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
// deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
||||
{
|
||||
rover.camera.control_msg(msg);
|
||||
|
@ -1376,14 +1397,14 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
#endif // CAMERA == ENABLED
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
||||
// deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
||||
case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
|
||||
{
|
||||
rover.camera_mount.configure_msg(msg);
|
||||
break;
|
||||
}
|
||||
|
||||
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
||||
// deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
||||
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
||||
{
|
||||
rover.camera_mount.control_msg(msg);
|
||||
|
@ -1460,7 +1481,9 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
void Rover::mavlink_delay_cb()
|
||||
{
|
||||
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;
|
||||
|
||||
|
|
Loading…
Reference in New Issue