mirror of https://github.com/ArduPilot/ardupilot
Rover: Change the IF statement to a SWITCH statement
This commit is contained in:
parent
7f97e897e2
commit
1e001fa017
|
@ -856,10 +856,14 @@ void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_messa
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for supported coordinate frames
|
// check for supported coordinate frames
|
||||||
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
|
switch (packet.coordinate_frame) {
|
||||||
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
|
case MAV_FRAME_LOCAL_NED:
|
||||||
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
|
case MAV_FRAME_LOCAL_OFFSET_NED:
|
||||||
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
|
case MAV_FRAME_BODY_NED:
|
||||||
|
case MAV_FRAME_BODY_OFFSET_NED:
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -975,14 +979,19 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// check for supported coordinate frames
|
// check for supported coordinate frames
|
||||||
if (packet.coordinate_frame != MAV_FRAME_GLOBAL &&
|
switch (packet.coordinate_frame) {
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
|
case MAV_FRAME_GLOBAL:
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT &&
|
case MAV_FRAME_GLOBAL_INT:
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
|
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT &&
|
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
|
||||||
|
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
||||||
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
|
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
|
||||||
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
|
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
|
||||||
|
|
Loading…
Reference in New Issue