Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
B
Baitboat
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Baitboat
Commits
b6db467e
Commit
b6db467e
authored
12 years ago
by
uncrustify
Committed by
Pat Hickey
12 years ago
Browse files
Options
Downloads
Patches
Plain Diff
uncrustify libraries/AP_AHRS/AP_AHRS.h
parent
b4571ca4
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
libraries/AP_AHRS/AP_AHRS.h
+141
-132
141 additions, 132 deletions
libraries/AP_AHRS/AP_AHRS.h
with
141 additions
and
132 deletions
libraries/AP_AHRS/AP_AHRS.h
+
141
−
132
View file @
b6db467e
#ifndef AP_AHRS_H
#ifndef AP_AHRS_H
#define AP_AHRS_H
#define AP_AHRS_H
/*
/*
AHRS (Attitude Heading Reference System) interface for ArduPilot
*
AHRS (Attitude Heading Reference System) interface for ArduPilot
*
This library is free software; you can redistribute it and/or
*
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
*
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
*
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*
version 2.1 of the License, or (at your option) any later version.
*/
*/
#include
<AP_Math.h>
#include
<AP_Math.h>
#include
<inttypes.h>
#include
<inttypes.h>
...
@@ -18,147 +18,156 @@
...
@@ -18,147 +18,156 @@
#include
<AP_Baro.h>
#include
<AP_Baro.h>
#if defined(ARDUINO) && ARDUINO >= 100
#if defined(ARDUINO) && ARDUINO >= 100
#include
"Arduino.h"
#include
"Arduino.h"
#else
#else
#include
"WProgram.h"
#include
"WProgram.h"
#endif
#endif
class
AP_AHRS
class
AP_AHRS
{
{
public:
public:
// Constructor
// Constructor
AP_AHRS
(
IMU
*
imu
,
GPS
*&
gps
)
:
AP_AHRS
(
IMU
*
imu
,
GPS
*&
gps
)
:
_imu
(
imu
),
_imu
(
imu
),
_gps
(
gps
),
_gps
(
gps
),
_barometer
(
NULL
)
_barometer
(
NULL
)
{
{
// base the ki values by the sensors maximum drift
// base the ki values by the sensors maximum drift
// rate. The APM2 has gyros which are much less drift
// rate. The APM2 has gyros which are much less drift
// prone than the APM1, so we should have a lower ki,
// prone than the APM1, so we should have a lower ki,
// which will make us less prone to increasing omegaI
// which will make us less prone to increasing omegaI
// incorrectly due to sensor noise
// incorrectly due to sensor noise
_gyro_drift_limit
=
imu
->
get_gyro_drift_rate
();
_gyro_drift_limit
=
imu
->
get_gyro_drift_rate
();
}
}
// empty init
// empty init
virtual
void
init
()
{};
virtual
void
init
()
{
};
// Accessors
void
set_fly_forward
(
bool
b
)
{
_fly_forward
=
b
;
}
// Accessors
void
set_compass
(
Compass
*
compass
)
{
_compass
=
compass
;
}
void
set_fly_forward
(
bool
b
)
{
void
set_barometer
(
AP_Baro
*
barometer
)
{
_barometer
=
barometer
;
}
_fly_forward
=
b
;
void
set_airspeed
(
AP_Airspeed
*
airspeed
)
{
_airspeed
=
airspeed
;
}
}
void
set_compass
(
Compass
*
compass
)
{
// Methods
_compass
=
compass
;
virtual
void
update
(
void
)
=
0
;
}
void
set_barometer
(
AP_Baro
*
barometer
)
{
// Euler angles (radians)
_barometer
=
barometer
;
float
roll
;
}
float
pitch
;
void
set_airspeed
(
AP_Airspeed
*
airspeed
)
{
float
yaw
;
_airspeed
=
airspeed
;
}
// integer Euler angles (Degrees * 100)
int32_t
roll_sensor
;
// Methods
int32_t
pitch_sensor
;
virtual
void
update
(
void
)
=
0
;
int32_t
yaw_sensor
;
// Euler angles (radians)
// return a smoothed and corrected gyro vector
float
roll
;
virtual
Vector3f
get_gyro
(
void
)
=
0
;
float
pitch
;
float
yaw
;
// return the current estimate of the gyro drift
virtual
Vector3f
get_gyro_drift
(
void
)
=
0
;
// integer Euler angles (Degrees * 100)
int32_t
roll_sensor
;
// reset the current attitude, used on new IMU calibration
int32_t
pitch_sensor
;
virtual
void
reset
(
bool
recover_eulers
=
false
)
=
0
;
int32_t
yaw_sensor
;
// how often our attitude representation has gone out of range
// return a smoothed and corrected gyro vector
uint8_t
renorm_range_count
;
virtual
Vector3f
get_gyro
(
void
)
=
0
;
// how often our attitude representation has blown up completely
// return the current estimate of the gyro drift
uint8_t
renorm_blowup_count
;
virtual
Vector3f
get_gyro_drift
(
void
)
=
0
;
// return the average size of the roll/pitch error estimate
// reset the current attitude, used on new IMU calibration
// since last call
virtual
void
reset
(
bool
recover_eulers
=
false
)
=
0
;
virtual
float
get_error_rp
(
void
)
=
0
;
// how often our attitude representation has gone out of range
// return the average size of the yaw error estimate
uint8_t
renorm_range_count
;
// since last call
virtual
float
get_error_yaw
(
void
)
=
0
;
// how often our attitude representation has blown up completely
uint8_t
renorm_blowup_count
;
// return a DCM rotation matrix representing our current
// attitude
// return the average size of the roll/pitch error estimate
virtual
Matrix3f
get_dcm_matrix
(
void
)
=
0
;
// since last call
virtual
float
get_error_rp
(
void
)
=
0
;
// get our current position, either from GPS or via
// dead-reckoning. Return true if a position is available,
// return the average size of the yaw error estimate
// otherwise false. This only updates the lat and lng fields
// since last call
// of the Location
virtual
float
get_error_yaw
(
void
)
=
0
;
bool
get_position
(
struct
Location
*
loc
)
{
if
(
!
_gps
||
_gps
->
status
()
!=
GPS
::
GPS_OK
)
{
// return a DCM rotation matrix representing our current
return
false
;
// attitude
}
virtual
Matrix3f
get_dcm_matrix
(
void
)
=
0
;
loc
->
lat
=
_gps
->
latitude
;
loc
->
lng
=
_gps
->
longitude
;
// get our current position, either from GPS or via
return
true
;
// dead-reckoning. Return true if a position is available,
}
// otherwise false. This only updates the lat and lng fields
// of the Location
// return a wind estimation vector, in m/s
bool
get_position
(
struct
Location
*
loc
)
{
Vector3f
wind_estimate
(
void
)
{
if
(
!
_gps
||
_gps
->
status
()
!=
GPS
::
GPS_OK
)
{
return
Vector3f
(
0
,
0
,
0
);
return
false
;
}
}
loc
->
lat
=
_gps
->
latitude
;
// return true if yaw has been initialised
loc
->
lng
=
_gps
->
longitude
;
bool
yaw_initialised
(
void
)
{
return
true
;
return
_have_initial_yaw
;
}
}
// return a wind estimation vector, in m/s
// set the fast gains flag
Vector3f
wind_estimate
(
void
)
{
void
set_fast_gains
(
bool
setting
)
{
return
Vector3f
(
0
,
0
,
0
);
_fast_ground_gains
=
setting
;
}
}
// return true if yaw has been initialised
// settable parameters
bool
yaw_initialised
(
void
)
{
AP_Float
_kp_yaw
;
return
_have_initial_yaw
;
AP_Float
_kp
;
}
AP_Float
gps_gain
;
AP_Int8
_gps_use
;
// set the fast gains flag
void
set_fast_gains
(
bool
setting
)
{
// for holding parameters
_fast_ground_gains
=
setting
;
static
const
struct
AP_Param
::
GroupInfo
var_info
[];
}
// settable parameters
AP_Float
_kp_yaw
;
AP_Float
_kp
;
AP_Float
gps_gain
;
AP_Int8
_gps_use
;
// for holding parameters
static
const
struct
AP_Param
::
GroupInfo
var_info
[];
protected
:
protected
:
// whether the yaw value has been intialised with a reference
// whether the yaw value has been intialised with a reference
bool
_have_initial_yaw
;
bool
_have_initial_yaw
;
// pointer to compass object, if available
// pointer to compass object, if available
Compass
*
_compass
;
Compass
*
_compass
;
// pointer to airspeed object, if available
// pointer to airspeed object, if available
AP_Airspeed
*
_airspeed
;
AP_Airspeed
*
_airspeed
;
// time in microseconds of last compass update
// time in microseconds of last compass update
uint32_t
_compass_last_update
;
uint32_t
_compass_last_update
;
// note: we use ref-to-pointer here so that our caller can change the GPS without our noticing
// note: we use ref-to-pointer here so that our caller can change the GPS without our noticing
// IMU under us without our noticing.
// IMU under us without our noticing.
IMU
*
_imu
;
IMU
*
_imu
;
GPS
*&
_gps
;
GPS
*&
_gps
;
AP_Baro
*
_barometer
;
AP_Baro
*
_barometer
;
// should we raise the gain on the accelerometers for faster
// should we raise the gain on the accelerometers for faster
// convergence, used when disarmed for ArduCopter
// convergence, used when disarmed for ArduCopter
bool
_fast_ground_gains
;
bool
_fast_ground_gains
;
// true if we can assume the aircraft will be flying forward
// true if we can assume the aircraft will be flying forward
// on its X axis
// on its X axis
bool
_fly_forward
;
bool
_fly_forward
;
// the limit of the gyro drift claimed by the sensors, in
// the limit of the gyro drift claimed by the sensors, in
// radians/s/s
// radians/s/s
float
_gyro_drift_limit
;
float
_gyro_drift_limit
;
// acceleration due to gravity in m/s/s
// acceleration due to gravity in m/s/s
static
const
float
_gravity
=
9.80665
;
static
const
float
_gravity
=
9.80665
;
};
};
#include
<AP_AHRS_DCM.h>
#include
<AP_AHRS_DCM.h>
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment