mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AC_WPNav: init flags
Resolves Coverity warning
This commit is contained in:
parent
bb382a65e8
commit
aa7a151fe5
@ -127,6 +127,14 @@ AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosContro
|
||||
_yaw(0.0f)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// init flags
|
||||
_flags.reached_destination = false;
|
||||
_flags.fast_waypoint = false;
|
||||
_flags.slowing_down = false;
|
||||
_flags.recalc_wp_leash = false;
|
||||
_flags.new_wp_destination = false;
|
||||
_flags.segment_type = SEGMENT_STRAIGHT;
|
||||
}
|
||||
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user