2017-02-11 04:14:23 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
* AHRS View class - for creating a 2nd view of the vehicle attitude
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "AP_AHRS.h"
|
2021-01-08 23:44:17 -04:00
|
|
|
#include <AP_Motors/AP_Motors.h>
|
|
|
|
|
|
|
|
// fwd declarations to avoid include errors
|
|
|
|
class AC_AttitudeControl;
|
|
|
|
class AC_PosControl;
|
2017-02-11 04:14:23 -04:00
|
|
|
|
|
|
|
class AP_AHRS_View
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
// Constructor
|
2018-11-12 00:58:54 -04:00
|
|
|
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation, float pitch_trim_deg=0);
|
2017-02-11 04:14:23 -04:00
|
|
|
|
|
|
|
// update state
|
2021-08-26 01:34:08 -03:00
|
|
|
void update();
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
// empty virtual destructor
|
|
|
|
virtual ~AP_AHRS_View() {}
|
|
|
|
|
|
|
|
// return a smoothed and corrected gyro vector
|
|
|
|
const Vector3f &get_gyro(void) const {
|
|
|
|
return gyro;
|
|
|
|
}
|
|
|
|
|
2017-03-02 07:33:13 -04:00
|
|
|
// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
|
|
|
|
Vector3f get_gyro_latest(void) const;
|
|
|
|
|
2019-03-06 20:38:24 -04:00
|
|
|
// return a DCM rotation matrix representing our current attitude in this view
|
2017-02-11 04:14:23 -04:00
|
|
|
const Matrix3f &get_rotation_body_to_ned(void) const {
|
|
|
|
return rot_body_to_ned;
|
|
|
|
}
|
|
|
|
|
2019-03-06 20:38:24 -04:00
|
|
|
// return a Quaternion representing our current attitude in this view
|
|
|
|
void get_quat_body_to_ned(Quaternion &quat) const {
|
|
|
|
quat.from_rotation_matrix(rot_body_to_ned);
|
|
|
|
}
|
|
|
|
|
2019-02-04 13:12:29 -04:00
|
|
|
// apply pitch trim
|
|
|
|
void set_pitch_trim(float trim_deg);
|
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
// helper trig value accessors
|
|
|
|
float cos_roll() const {
|
|
|
|
return trig.cos_roll;
|
|
|
|
}
|
|
|
|
float cos_pitch() const {
|
|
|
|
return trig.cos_pitch;
|
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
float cos_yaw() const {
|
2017-02-11 04:14:23 -04:00
|
|
|
return trig.cos_yaw;
|
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
float sin_roll() const {
|
2017-02-11 04:14:23 -04:00
|
|
|
return trig.sin_roll;
|
|
|
|
}
|
|
|
|
float sin_pitch() const {
|
|
|
|
return trig.sin_pitch;
|
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
float sin_yaw() const {
|
2017-02-11 04:14:23 -04:00
|
|
|
return trig.sin_yaw;
|
|
|
|
}
|
|
|
|
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
/*
|
|
|
|
wrappers around ahrs functions which pass-thru directly. See
|
|
|
|
AP_AHRS.h for description of each function
|
|
|
|
*/
|
2023-02-02 18:58:38 -04:00
|
|
|
bool get_location(Location &loc) const WARN_IF_UNUSED {
|
2022-01-20 19:42:40 -04:00
|
|
|
return ahrs.get_location(loc);
|
2017-02-11 04:14:23 -04:00
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2023-01-12 03:12:01 -04:00
|
|
|
bool wind_estimate(Vector3f &wind) {
|
|
|
|
return ahrs.wind_estimate(wind);
|
2017-02-11 04:14:23 -04:00
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2020-01-06 20:45:58 -04:00
|
|
|
bool airspeed_estimate(float &airspeed_ret) const WARN_IF_UNUSED {
|
2017-02-11 04:14:23 -04:00
|
|
|
return ahrs.airspeed_estimate(airspeed_ret);
|
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2020-01-06 20:45:58 -04:00
|
|
|
bool airspeed_estimate_true(float &airspeed_ret) const WARN_IF_UNUSED {
|
2017-02-11 04:14:23 -04:00
|
|
|
return ahrs.airspeed_estimate_true(airspeed_ret);
|
|
|
|
}
|
|
|
|
|
|
|
|
float get_EAS2TAS(void) const {
|
|
|
|
return ahrs.get_EAS2TAS();
|
|
|
|
}
|
|
|
|
|
|
|
|
Vector2f groundspeed_vector(void) {
|
|
|
|
return ahrs.groundspeed_vector();
|
|
|
|
}
|
|
|
|
|
2019-03-12 06:59:19 -03:00
|
|
|
bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED {
|
2017-02-11 04:14:23 -04:00
|
|
|
return ahrs.get_velocity_NED(vec);
|
|
|
|
}
|
|
|
|
|
2019-03-12 06:59:19 -03:00
|
|
|
bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED {
|
2017-02-12 21:02:33 -04:00
|
|
|
return ahrs.get_relative_position_NED_home(vec);
|
2017-02-11 04:14:23 -04:00
|
|
|
}
|
|
|
|
|
2019-03-12 06:59:19 -03:00
|
|
|
bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED {
|
2017-02-12 21:02:33 -04:00
|
|
|
return ahrs.get_relative_position_NED_origin(vec);
|
|
|
|
}
|
2019-02-19 23:53:28 -04:00
|
|
|
|
2019-03-12 06:59:19 -03:00
|
|
|
bool get_relative_position_NE_home(Vector2f &vecNE) const WARN_IF_UNUSED {
|
2017-02-12 21:02:33 -04:00
|
|
|
return ahrs.get_relative_position_NE_home(vecNE);
|
2017-02-11 04:14:23 -04:00
|
|
|
}
|
|
|
|
|
2019-03-12 06:59:19 -03:00
|
|
|
bool get_relative_position_NE_origin(Vector2f &vecNE) const WARN_IF_UNUSED {
|
2017-02-12 21:02:33 -04:00
|
|
|
return ahrs.get_relative_position_NE_origin(vecNE);
|
|
|
|
}
|
2019-02-19 23:53:28 -04:00
|
|
|
|
2017-02-19 23:31:53 -04:00
|
|
|
void get_relative_position_D_home(float &posD) const {
|
|
|
|
ahrs.get_relative_position_D_home(posD);
|
2017-02-11 04:14:23 -04:00
|
|
|
}
|
|
|
|
|
2019-03-12 06:59:19 -03:00
|
|
|
bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED {
|
2017-02-19 23:31:53 -04:00
|
|
|
return ahrs.get_relative_position_D_origin(posD);
|
2017-02-12 21:02:33 -04:00
|
|
|
}
|
2019-02-19 23:53:28 -04:00
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
float groundspeed(void) {
|
|
|
|
return ahrs.groundspeed();
|
|
|
|
}
|
|
|
|
|
2022-07-26 21:21:01 -03:00
|
|
|
const Vector3f &get_accel_ef(void) const {
|
|
|
|
return ahrs.get_accel_ef();
|
2017-02-11 04:14:23 -04:00
|
|
|
}
|
|
|
|
|
2019-12-10 05:32:52 -04:00
|
|
|
uint32_t getLastPosNorthEastReset(Vector2f &pos) WARN_IF_UNUSED {
|
2017-02-11 04:14:23 -04:00
|
|
|
return ahrs.getLastPosNorthEastReset(pos);
|
|
|
|
}
|
|
|
|
|
2019-12-10 05:32:52 -04:00
|
|
|
uint32_t getLastPosDownReset(float &posDelta) WARN_IF_UNUSED {
|
2017-02-11 04:14:23 -04:00
|
|
|
return ahrs.getLastPosDownReset(posDelta);
|
|
|
|
}
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2017-09-04 03:53:56 -03:00
|
|
|
// rotate a 2D vector from earth frame to body frame
|
|
|
|
// in result, x is forward, y is right
|
2020-06-01 21:16:33 -03:00
|
|
|
Vector2f earth_to_body2D(const Vector2f &ef_vector) const;
|
2017-09-04 03:53:56 -03:00
|
|
|
|
|
|
|
// rotate a 2D vector from earth frame to body frame
|
|
|
|
// in input, x is forward, y is right
|
2020-06-01 21:16:33 -03:00
|
|
|
Vector2f body_to_earth2D(const Vector2f &bf) const;
|
2019-02-19 23:53:28 -04:00
|
|
|
|
2017-03-30 20:32:33 -03:00
|
|
|
// return the average size of the roll/pitch error estimate
|
|
|
|
// since last call
|
|
|
|
float get_error_rp(void) const {
|
|
|
|
return ahrs.get_error_rp();
|
|
|
|
}
|
|
|
|
|
|
|
|
// return the average size of the yaw error estimate
|
|
|
|
// since last call
|
|
|
|
float get_error_yaw(void) const {
|
|
|
|
return ahrs.get_error_yaw();
|
|
|
|
}
|
2019-02-19 23:53:28 -04:00
|
|
|
|
2021-01-08 23:44:17 -04:00
|
|
|
// Logging Functions
|
|
|
|
void Write_AttitudeView(const Vector3f &targets) const;
|
|
|
|
void Write_Rate( const AP_Motors &motors, const AC_AttitudeControl &attitude_control,
|
|
|
|
const AC_PosControl &pos_control) const;
|
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
float roll;
|
|
|
|
float pitch;
|
|
|
|
float yaw;
|
|
|
|
int32_t roll_sensor;
|
|
|
|
int32_t pitch_sensor;
|
|
|
|
int32_t yaw_sensor;
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2021-08-12 19:57:26 -03:00
|
|
|
|
|
|
|
// get current rotation
|
2022-04-19 19:45:10 -03:00
|
|
|
// note that this may not be the rotation were actually using, see _pitch_trim_deg
|
2021-08-12 19:57:26 -03:00
|
|
|
enum Rotation get_rotation(void) const {
|
|
|
|
return rotation;
|
|
|
|
}
|
|
|
|
|
2022-04-19 19:45:10 -03:00
|
|
|
// get pitch trim (deg)
|
|
|
|
float get_pitch_trim() const { return _pitch_trim_deg; }
|
|
|
|
|
2022-06-16 19:42:39 -03:00
|
|
|
// Rotate vector from AHRS reference frame to AHRS view refences frame
|
|
|
|
void rotate(Vector3f &vec) const;
|
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
private:
|
|
|
|
const enum Rotation rotation;
|
|
|
|
AP_AHRS &ahrs;
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2019-03-23 13:45:57 -03:00
|
|
|
// body frame rotation for this View
|
2017-02-11 04:15:34 -04:00
|
|
|
Matrix3f rot_view;
|
2019-03-23 13:45:57 -03:00
|
|
|
// transpose of rot_view
|
|
|
|
Matrix3f rot_view_T;
|
2017-02-11 04:14:23 -04:00
|
|
|
Matrix3f rot_body_to_ned;
|
|
|
|
Vector3f gyro;
|
2017-02-11 04:15:34 -04:00
|
|
|
|
2017-02-11 04:14:23 -04:00
|
|
|
struct {
|
|
|
|
float cos_roll;
|
|
|
|
float cos_pitch;
|
|
|
|
float cos_yaw;
|
|
|
|
float sin_roll;
|
|
|
|
float sin_pitch;
|
|
|
|
float sin_yaw;
|
|
|
|
} trig;
|
2018-09-25 12:14:36 -03:00
|
|
|
|
|
|
|
float y_angle;
|
2019-02-04 13:12:29 -04:00
|
|
|
float _pitch_trim_deg;
|
2017-02-11 04:14:23 -04:00
|
|
|
};
|