Copter: Enable processing
This commit is contained in:
parent
f7cc7eea90
commit
da3a9c1cc6
@ -414,11 +414,14 @@ bool ModeGuided::get_wp(Location& destination) const
|
|||||||
case SubMode::Pos:
|
case SubMode::Pos:
|
||||||
destination = Location(guided_pos_target_cm.tofloat(), guided_pos_terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
|
destination = Location(guided_pos_target_cm.tofloat(), guided_pos_terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
|
||||||
return true;
|
return true;
|
||||||
default:
|
case SubMode::Angle:
|
||||||
return false;
|
case SubMode::TakeOff:
|
||||||
|
case SubMode::Accel:
|
||||||
|
case SubMode::VelAccel:
|
||||||
|
case SubMode::PosVelAccel:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// should never get here but just in case
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user