Browse Source

AC_Circle: init members and flags

Removed unused dir flag
Resolves Coverity warning
mission-4.1.18
Randy Mackay 10 years ago
parent
commit
bb382a65e8
  1. 4
      libraries/AC_WPNav/AC_Circle.cpp
  2. 1
      libraries/AC_WPNav/AC_Circle.h

4
libraries/AC_WPNav/AC_Circle.cpp

@ -35,6 +35,7 @@ AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosCont @@ -35,6 +35,7 @@ AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosCont
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),
_last_update(0),
_yaw(0.0f),
_angle(0.0f),
_angle_total(0.0f),
@ -43,6 +44,9 @@ AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosCont @@ -43,6 +44,9 @@ AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosCont
_angular_accel(0.0f)
{
AP_Param::setup_object_defaults(this, var_info);
// init flags
_flags.panorama = false;
}
/// init - initialise circle controller setting center specifically

1
libraries/AC_WPNav/AC_Circle.h

@ -78,7 +78,6 @@ private: @@ -78,7 +78,6 @@ private:
// flags structure
struct circle_flags {
uint8_t panorama : 1; // true if we are doing a panorama
uint8_t dir : 1; // 0 = clockwise, 1 = counter clockwise
} _flags;
// references to inertial nav and ahrs libraries

Loading…
Cancel
Save