AP_Compass: revert compass parameter changes

This commit is contained in:
Andrew Tridgell 2021-12-04 15:22:56 +11:00
parent e7c7cdd653
commit 8eb40bafc5
7 changed files with 235 additions and 469 deletions

File diff suppressed because it is too large Load Diff

View File

@ -14,7 +14,6 @@
#include "AP_Compass_Backend.h"
#include "Compass_PerMotor.h"
#include <AP_Common/TSIndex.h>
#include "AP_Compass_Params.h"
// motor compensation types (for use with motor_comp_enabled)
#define AP_COMPASS_MOT_COMP_DISABLED 0x00
@ -207,13 +206,13 @@ public:
///
/// @returns The current compass offsets in milligauss.
///
const Vector3f &get_offsets(uint8_t i) const { return _get_state(Priority(i)).params.offset; }
const Vector3f &get_offsets(uint8_t i) const { return _get_state(Priority(i)).offset; }
const Vector3f &get_offsets(void) const { return get_offsets(_first_usable); }
const Vector3f &get_diagonals(uint8_t i) const { return _get_state(Priority(i)).params.diagonals; }
const Vector3f &get_diagonals(uint8_t i) const { return _get_state(Priority(i)).diagonals; }
const Vector3f &get_diagonals(void) const { return get_diagonals(_first_usable); }
const Vector3f &get_offdiagonals(uint8_t i) const { return _get_state(Priority(i)).params.offdiagonals; }
const Vector3f &get_offdiagonals(uint8_t i) const { return _get_state(Priority(i)).offdiagonals; }
const Vector3f &get_offdiagonals(void) const { return get_offdiagonals(_first_usable); }
// learn offsets accessor
@ -258,7 +257,7 @@ public:
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor);
/// get motor compensation factors as a vector
const Vector3f& get_motor_compensation(uint8_t i) const { return _get_state(Priority(i)).params.motor_compensation; }
const Vector3f& get_motor_compensation(uint8_t i) const { return _get_state(Priority(i)).motor_compensation; }
const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(_first_usable); }
/// Saves the current motor compensation x/y/z values.
@ -484,15 +483,28 @@ private:
float _thr;
struct mag_state {
AP_Int8 external;
bool healthy;
bool registered;
Compass::Priority priority;
AP_Int8 orientation;
AP_Vector3f offset;
AP_Vector3f diagonals;
AP_Vector3f offdiagonals;
AP_Float scale_factor;
// device id detected at init.
// saved to eeprom when offsets are saved allowing ram &
// eeprom values to be compared as consistency check
AP_Int32 dev_id;
// Initialised when compass is detected
int32_t detected_dev_id;
// Initialised at boot from saved devid
int32_t expected_dev_id;
// factors multiplied by throttle and added to compass outputs
AP_Vector3f motor_compensation;
// latest compensation added to compass
Vector3f motor_offset;
@ -511,8 +523,6 @@ private:
uint32_t accum_count;
// We only copy persistent params
void copy_from(const mag_state& state);
AP_Compass_Params params;
};
//Create an Array of mag_state to be accessible by StateIndex only
@ -544,6 +554,7 @@ private:
void _reset_compass_id();
//Create Arrays to be accessible by Priority only
RestrictIDTypeArray<AP_Int8, COMPASS_MAX_INSTANCES, Priority> _use_for_yaw;
#if COMPASS_MAX_INSTANCES > 1
RestrictIDTypeArray<AP_Int32, COMPASS_MAX_INSTANCES, Priority> _priority_did_stored_list;
RestrictIDTypeArray<int32_t, COMPASS_MAX_INSTANCES, Priority> _priority_did_list;
@ -598,9 +609,6 @@ private:
bool init_done;
uint8_t _first_usable; // first compass usable based on COMPASSx_USE param
// convet params to per instance param table
void convert_per_instance();
};
namespace AP {

View File

@ -21,7 +21,7 @@ void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)
}
mag.rotate(state.rotation);
if (!state.params.external) {
if (!state.external) {
// and add in AHRS_ORIENTATION setting if not an external compass
if (_compass._board_orientation == ROTATION_CUSTOM && _compass._custom_rotation) {
mag = *_compass._custom_rotation * mag;
@ -31,14 +31,14 @@ void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)
} else {
// add user selectable orientation
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
Rotation rotation = Rotation(state.params.orientation.get());
Rotation rotation = Rotation(state.orientation.get());
if (rotation == ROTATION_CUSTOM && _compass._custom_external_rotation) {
mag = *_compass._custom_external_rotation * mag;
} else {
mag.rotate(rotation);
}
#else
mag.rotate((enum Rotation)state.params.orientation.get());
mag.rotate((enum Rotation)state.orientation.get());
#endif
}
}
@ -62,13 +62,13 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
{
Compass::mag_state &state = _compass._state[Compass::StateIndex(i)];
if (state.params.diagonals.get().is_zero()) {
state.params.diagonals.set(Vector3f(1.0f,1.0f,1.0f));
if (state.diagonals.get().is_zero()) {
state.diagonals.set(Vector3f(1.0f,1.0f,1.0f));
}
const Vector3f &offsets = state.params.offset.get();
const Vector3f &diagonals = state.params.diagonals.get();
const Vector3f &offdiagonals = state.params.offdiagonals.get();
const Vector3f &offsets = state.offset.get();
const Vector3f &diagonals = state.diagonals.get();
const Vector3f &offdiagonals = state.offdiagonals.get();
// add in the basic offsets
mag += offsets;
@ -76,7 +76,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
// add in scale factor, use a wide sanity check. The calibrator
// uses a narrower check.
if (_compass.have_scale_factor(i)) {
mag *= state.params.scale_factor;
mag *= state.scale_factor;
}
// apply eliptical correction
@ -89,7 +89,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
mag = mat * mag;
#if COMPASS_MOT_ENABLED
const Vector3f &mot = state.params.motor_compensation.get();
const Vector3f &mot = state.motor_compensation.get();
/*
calculate motor-power based compensation
note that _motor_offset[] is kept even if compensation is not
@ -202,7 +202,7 @@ bool AP_Compass_Backend::register_compass(int32_t dev_id, uint8_t& instance) con
*/
void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
{
_compass._state[Compass::StateIndex(instance)].params.dev_id.set_and_notify(dev_id);
_compass._state[Compass::StateIndex(instance)].dev_id.set_and_notify(dev_id);
_compass._state[Compass::StateIndex(instance)].detected_dev_id = dev_id;
}
@ -211,7 +211,7 @@ void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
*/
void AP_Compass_Backend::save_dev_id(uint8_t instance)
{
_compass._state[Compass::StateIndex(instance)].params.dev_id.save();
_compass._state[Compass::StateIndex(instance)].dev_id.save();
}
/*
@ -219,14 +219,14 @@ void AP_Compass_Backend::save_dev_id(uint8_t instance)
*/
void AP_Compass_Backend::set_external(uint8_t instance, bool external)
{
if (_compass._state[Compass::StateIndex(instance)].params.external != 2) {
_compass._state[Compass::StateIndex(instance)].params.external.set_and_notify(external);
if (_compass._state[Compass::StateIndex(instance)].external != 2) {
_compass._state[Compass::StateIndex(instance)].external.set_and_notify(external);
}
}
bool AP_Compass_Backend::is_external(uint8_t instance)
{
return _compass._state[Compass::StateIndex(instance)].params.external;
return _compass._state[Compass::StateIndex(instance)].external;
}
// set rotation of an instance
@ -235,7 +235,7 @@ void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation)
_compass._state[Compass::StateIndex(instance)].rotation = rotation;
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
// lazily create the custom rotation matrix
if (!_compass._custom_external_rotation && Rotation(_compass._state[Compass::StateIndex(instance)].params.orientation.get()) == ROTATION_CUSTOM) {
if (!_compass._custom_external_rotation && Rotation(_compass._state[Compass::StateIndex(instance)].orientation.get()) == ROTATION_CUSTOM) {
_compass._custom_external_rotation = new Matrix3f();
if (_compass._custom_external_rotation) {
_compass._custom_external_rotation->from_euler(radians(_compass._custom_roll), radians(_compass._custom_pitch), radians(_compass._custom_yaw));

View File

@ -81,13 +81,13 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
}
if (_rotate_auto) {
enum Rotation r = _get_state(prio).params.external?(enum Rotation)_get_state(prio).params.orientation.get():ROTATION_NONE;
enum Rotation r = _get_state(prio).external?(enum Rotation)_get_state(prio).orientation.get():ROTATION_NONE;
if (r != ROTATION_CUSTOM) {
_calibrator[prio]->set_orientation(r, _get_state(prio).params.external, _rotate_auto>=2, _rotate_auto>=3);
_calibrator[prio]->set_orientation(r, _get_state(prio).external, _rotate_auto>=2, _rotate_auto>=3);
}
}
_cal_saved[prio] = false;
if (i == 0 && _get_state(prio).params.external != 0) {
if (i == 0 && _get_state(prio).external != 0) {
_calibrator[prio]->start(retry, delay, get_offsets_max(), i, _calibration_threshold);
} else {
// internal compasses or secondary compasses get twice the
@ -207,7 +207,7 @@ bool Compass::_accept_calibration(uint8_t i)
set_and_save_offdiagonals(i,offdiag);
set_and_save_scale_factor(i,scale_factor);
if (cal_report.check_orientation && _get_state(prio).params.external && _rotate_auto >= 2) {
if (cal_report.check_orientation && _get_state(prio).external && _rotate_auto >= 2) {
set_and_save_orientation(i, cal_report.orientation);
}

View File

@ -1,140 +0,0 @@
#include "AP_Compass_Params.h"
#include "AP_Compass.h"
const AP_Param::GroupInfo AP_Compass_Params::var_info[] = {
// @Param: USE
// @DisplayName: Use compass for yaw
// @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("USE", 1, AP_Compass_Params, use_for_yaw, 1), // true if used for DCM yaw
// @Param: ORIENT
// @DisplayName: Compass orientation
// @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation.
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom
// @User: Advanced
AP_GROUPINFO("ORIENT", 2, AP_Compass_Params, orientation, ROTATION_NONE),
// @Param: EXTERN
// @DisplayName: Compass is attached via an external cable
// @Description: Configure compass so it is attached externally. This is auto-detected on most boards. Set to 1 if the compass is externally connected. When externally connected the COMPASSx_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
// @Values: 0:Internal,1:External,2:ForcedExternal
// @User: Advanced
AP_GROUPINFO("EXTERN", 3, AP_Compass_Params, external, 0),
// @Param: DEV_ID
// @DisplayName: Compass device id
// @Description: Compass device id. Automatically detected, do not set manually
// @ReadOnly: True
// @User: Advanced
AP_GROUPINFO("DEV_ID", 4, AP_Compass_Params, dev_id, 0),
// @Param: OFS_X
// @DisplayName: Compass offsets in milligauss on the X axis
// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: mGauss
// @Increment: 1
// @User: Advanced
// @Calibration: 1
// @Param: OFS_Y
// @DisplayName: Compass offsets in milligauss on the Y axis
// @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: mGauss
// @Increment: 1
// @User: Advanced
// @Calibration: 1
// @Param: OFS_Z
// @DisplayName: Compass offsets in milligauss on the Z axis
// @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: mGauss
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("OFS", 5, AP_Compass_Params, offset, 0),
#ifndef HAL_BUILD_AP_PERIPH
// @Param: DIA_X
// @DisplayName: Compass soft-iron diagonal X component
// @Description: DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
// @User: Advanced
// @Calibration: 1
// @Param: DIA_Y
// @DisplayName: Compass soft-iron diagonal Y component
// @Description: DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
// @User: Advanced
// @Calibration: 1
// @Param: DIA_Z
// @DisplayName: Compass soft-iron diagonal Z component
// @Description: DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
// @User: Advanced
AP_GROUPINFO("DIA", 6, AP_Compass_Params, diagonals, 0),
// @Param: ODI_X
// @DisplayName: Compass soft-iron off-diagonal X component
// @Description: ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
// @User: Advanced
// @Calibration: 1
// @Param: ODI_Y
// @DisplayName: Compass soft-iron off-diagonal Y component
// @Description: ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
// @User: Advanced
// @Calibration: 1
// @Param: ODI_Z
// @DisplayName: Compass soft-iron off-diagonal Z component
// @Description: ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
// @User: Advanced
AP_GROUPINFO("ODI", 7, AP_Compass_Params, offdiagonals, 0),
// @Param: SCALE
// @DisplayName: Compass1 scale factor
// @Description: Scaling factor for first compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
// @User: Standard
// @Range: 0 1.3
AP_GROUPINFO("SCALE", 8, AP_Compass_Params, scale_factor, 0),
#endif // HAL_BUILD_AP_PERIPH
#if COMPASS_MOT_ENABLED
// @Param: MOT_X
// @DisplayName: Motor interference compensation for body frame X axis
// @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @Calibration: 1
// @Param: MOT_Y
// @DisplayName: Motor interference compensation for body frame Y axis
// @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @Calibration: 1
// @Param: MOT_Z
// @DisplayName: Motor interference compensation for body frame Z axis
// @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("MOT", 9, AP_Compass_Params, motor_compensation, 0),
#endif
AP_GROUPEND
};
AP_Compass_Params::AP_Compass_Params(void) {
AP_Param::setup_object_defaults(this, var_info);
}

View File

@ -1,34 +0,0 @@
#pragma once
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
class AP_Compass_Params {
public:
static const struct AP_Param::GroupInfo var_info[];
AP_Compass_Params(void);
/* Do not allow copies */
AP_Compass_Params(const AP_Compass_Params &other) = delete;
AP_Compass_Params &operator=(const AP_Compass_Params&) = delete;
AP_Int8 use_for_yaw;
AP_Int8 orientation;
AP_Int8 external;
// device id detected at init.
// saved to eeprom when offsets are saved allowing ram &
// eeprom values to be compared as consistency check
AP_Int32 dev_id;
AP_Vector3f offset;
AP_Vector3f diagonals;
AP_Vector3f offdiagonals;
AP_Float scale_factor;
// factors multiplied by throttle and added to compass outputs
AP_Vector3f motor_compensation;
};

View File

@ -37,9 +37,9 @@ AP_Compass_SITL::AP_Compass_SITL()
// we want to simulate a calibrated compass by default, so set
// scale to 1
AP_Param::set_default_by_name("COMPASS1_SCALE", 1);
AP_Param::set_default_by_name("COMPASS2_SCALE", 1);
AP_Param::set_default_by_name("COMPASS3_SCALE", 1);
AP_Param::set_default_by_name("COMPASS_SCALE", 1);
AP_Param::set_default_by_name("COMPASS_SCALE2", 1);
AP_Param::set_default_by_name("COMPASS_SCALE3", 1);
// make first compass external
set_external(_compass_instance[0], true);