mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AC_Circle: init members and flags
Removed unused dir flag Resolves Coverity warning
This commit is contained in:
parent
1bf0139162
commit
bb382a65e8
@ -35,6 +35,7 @@ AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosCont
|
|||||||
_inav(inav),
|
_inav(inav),
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
_pos_control(pos_control),
|
_pos_control(pos_control),
|
||||||
|
_last_update(0),
|
||||||
_yaw(0.0f),
|
_yaw(0.0f),
|
||||||
_angle(0.0f),
|
_angle(0.0f),
|
||||||
_angle_total(0.0f),
|
_angle_total(0.0f),
|
||||||
@ -43,6 +44,9 @@ AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosCont
|
|||||||
_angular_accel(0.0f)
|
_angular_accel(0.0f)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
|
||||||
|
// init flags
|
||||||
|
_flags.panorama = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// init - initialise circle controller setting center specifically
|
/// init - initialise circle controller setting center specifically
|
||||||
|
@ -78,7 +78,6 @@ private:
|
|||||||
// flags structure
|
// flags structure
|
||||||
struct circle_flags {
|
struct circle_flags {
|
||||||
uint8_t panorama : 1; // true if we are doing a panorama
|
uint8_t panorama : 1; // true if we are doing a panorama
|
||||||
uint8_t dir : 1; // 0 = clockwise, 1 = counter clockwise
|
|
||||||
} _flags;
|
} _flags;
|
||||||
|
|
||||||
// references to inertial nav and ahrs libraries
|
// references to inertial nav and ahrs libraries
|
||||||
|
Loading…
Reference in New Issue
Block a user