From da3a9c1cc66756cf17538c9538818dd7675a20ee Mon Sep 17 00:00:00 2001 From: muramura Date: Wed, 22 May 2024 21:26:48 +0900 Subject: [PATCH] Copter: Enable processing --- ArduCopter/mode_guided.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 35df242985..660c94eef1 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -414,11 +414,14 @@ bool ModeGuided::get_wp(Location& destination) const case SubMode::Pos: destination = Location(guided_pos_target_cm.tofloat(), guided_pos_terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); return true; - default: - return false; + case SubMode::Angle: + case SubMode::TakeOff: + case SubMode::Accel: + case SubMode::VelAccel: + case SubMode::PosVelAccel: + break; } - // should never get here but just in case return false; }