From 490571ba4433558fd500dbb160eb10e94e039589 Mon Sep 17 00:00:00 2001 From: murata Date: Fri, 23 Dec 2016 18:49:39 +0900 Subject: [PATCH] Rover: Changed if statements to switch statement. Rover: Changed if statements to switch statement. --- APMrover2/GCS_Mavlink.cpp | 15 +++++++++++---- APMrover2/control_modes.cpp | 16 +++++++++++++--- 2 files changed, 24 insertions(+), 7 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index b6c6e79c6f..1a83cdf19d 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1271,20 +1271,27 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) // prepare and send target position if (!pos_ignore) { Location loc = rover.current_loc; - if (packet.coordinate_frame == MAV_FRAME_BODY_NED || - packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) { + switch (packet.coordinate_frame) { + case MAV_FRAME_BODY_NED: + case MAV_FRAME_BODY_OFFSET_NED: { // rotate from body-frame to NE frame float ne_x = packet.x*rover.ahrs.cos_yaw() - packet.y*rover.ahrs.sin_yaw(); float ne_y = packet.x*rover.ahrs.sin_yaw() + packet.y*rover.ahrs.cos_yaw(); // add offset to current location location_offset(loc, ne_x, ne_y); - } else if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED) { + } + break; + + case MAV_FRAME_LOCAL_OFFSET_NED: // add offset to current location location_offset(loc, packet.x, packet.y); - } else { + break; + + default: // MAV_FRAME_LOCAL_NED interpret as an offset from home loc = rover.ahrs.get_home(); location_offset(loc, packet.x, packet.y); + break; } rover.guided_WP = loc; diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index 3b196513c5..457a261f87 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -80,7 +80,8 @@ void Rover::read_trim_switch() if (ch7_flag) { ch7_flag = false; - if (control_mode == MANUAL) { + switch (control_mode) { + case MANUAL: hal.console->println("Erasing waypoints"); // if SW7 is ON in MANUAL = Erase the Flight Plan mission.clear(); @@ -89,7 +90,9 @@ void Rover::read_trim_switch() init_home(); } return; - } else if (control_mode == LEARNING || control_mode == STEERING) { + + case LEARNING: + case STEERING: { // if SW7 is ON in LEARNING = record the Wp // create new mission command @@ -105,9 +108,16 @@ void Rover::read_trim_switch() if(mission.add_cmd(cmd)) { hal.console->printf("Learning waypoint %u", (unsigned)mission.num_commands()); } - } else if (control_mode == AUTO) { + } + break; + + case AUTO: // if SW7 is ON in AUTO = set to RTL set_mode(RTL); + break; + + default: + break; } } }