Compass: add ORIENT2 and EXTERNAL2 params

This commit is contained in:
Randy Mackay 2014-09-24 22:26:42 +09:00 committed by Andrew Tridgell
parent 16058cb730
commit 023b6afe8b
2 changed files with 48 additions and 4 deletions

View File

@ -89,14 +89,14 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
// @DisplayName: Compass orientation
// @Description: The orientation of the compass relative to the autopilot board. This will default to the right value for each board type, but can be changed if you have an external compass. See the documentation for your external compass for the right value. The correct orientation should give the X axis forward, the Y axis to the right and the Z axis down. So if your aircraft is pointing west it should show a positive value for the Y axis, and a value close to zero for the X axis. On a PX4 or Pixhawk with an external compass the correct value is zero if the compass is correctly oriented. NOTE: This orientation is combined with any AHRS_ORIENTATION setting.
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270
AP_GROUPINFO("ORIENT", 8, Compass, _orientation, ROTATION_NONE),
AP_GROUPINFO("ORIENT", 8, Compass, _orientation[0], ROTATION_NONE),
// @Param: EXTERNAL
// @DisplayName: Compass is attached via an external cable
// @Description: Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk, but must be set correctly on an APM2. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option
// @Values: 0:Internal,1:External
// @User: Advanced
AP_GROUPINFO("EXTERNAL", 9, Compass, _external, 0),
AP_GROUPINFO("EXTERNAL", 9, Compass, _external[0], 0),
#if COMPASS_MAX_INSTANCES > 1
// @Param: OFS2_X
@ -213,6 +213,50 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
AP_GROUPINFO("DEV_ID3", 17, Compass, _dev_id[2], 0),
#endif
#if COMPASS_MAX_INSTANCES > 1
// @Param: USE2
// @DisplayName: Compass2 used for yaw
// @Description: Enable or disable the second compass for determining heading.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("USE2", 18, Compass, _use_for_yaw[1], 1),
// @Param: ORIENT2
// @DisplayName: Compass2 orientation
// @Description: The orientation of the second compass relative to the frame (if external) or autopilot board (if internal).
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270
AP_GROUPINFO("ORIENT2", 19, Compass, _orientation[1], ROTATION_NONE),
// @Param: EXTERNAL2
// @DisplayName: Compass2 is attached via an external cable
// @Description: Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk.
// @Values: 0:Internal,1:External
// @User: Advanced
AP_GROUPINFO("EXTERNAL2",20, Compass, _external[1], 0),
#endif
#if COMPASS_MAX_INSTANCES > 2
// @Param: USE3
// @DisplayName: Compass3 used for yaw
// @Description: Enable or disable the third compass for determining heading.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("USE3", 21, Compass, _use_for_yaw[2], 1),
// @Param: ORIENT3
// @DisplayName: Compass3 orientation
// @Description: The orientation of the third compass relative to the frame (if external) or autopilot board (if internal).
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270
AP_GROUPINFO("ORIENT3", 22, Compass, _orientation[2], ROTATION_NONE),
// @Param: EXTERNAL3
// @DisplayName: Compass3 is attached via an external cable
// @Description: Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk.
// @Values: 0:Internal,1:External
// @User: Advanced
AP_GROUPINFO("EXTERNAL3",23, Compass, _external[2], 0),
#endif
AP_GROUPEND
};

View File

@ -249,12 +249,12 @@ protected:
bool _healthy[COMPASS_MAX_INSTANCES];
Vector3f _field[COMPASS_MAX_INSTANCES]; ///< magnetic field strength
AP_Int8 _orientation;
AP_Int8 _orientation[COMPASS_MAX_INSTANCES];
AP_Vector3f _offset[COMPASS_MAX_INSTANCES];
AP_Float _declination;
AP_Int8 _use_for_yaw[COMPASS_MAX_INSTANCES];///<enable use for yaw calculation
AP_Int8 _auto_declination; ///<enable automatic declination code
AP_Int8 _external; ///<compass is external
AP_Int8 _external[COMPASS_MAX_INSTANCES]; ///<compass is external
#if COMPASS_MAX_INSTANCES > 1
AP_Int8 _primary; ///primary instance
AP_Int32 _dev_id[COMPASS_MAX_INSTANCES]; // device id detected at init. saved to eeprom when offsets are saved allowing ram & eeprom values to be compared as consistency check