mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: default YAW_CORR to 0
The default of 22 was good when the Lightware SF40C was our only proximity sensor but not good now that we have numerous options
This commit is contained in:
parent
ff3d3d256c
commit
2061621951
|
@ -50,7 +50,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||
// @Units: deg
|
||||
// @Range: -180 180
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], PROXIMITY_YAW_CORRECTION_DEFAULT),
|
||||
AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], 0),
|
||||
|
||||
// @Param: _IGN_ANG1
|
||||
// @DisplayName: Proximity sensor ignore angle 1
|
||||
|
@ -170,7 +170,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||
// @Units: deg
|
||||
// @Range: -180 180
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("2_YAW_CORR", 18, AP_Proximity, _yaw_correction[1], PROXIMITY_YAW_CORRECTION_DEFAULT),
|
||||
AP_GROUPINFO("2_YAW_CORR", 18, AP_Proximity, _yaw_correction[1], 0),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
|
|
|
@ -22,7 +22,6 @@
|
|||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
|
||||
#define PROXIMITY_MAX_INSTANCES 1 // Maximum number of proximity sensor instances available on this platform
|
||||
#define PROXIMITY_YAW_CORRECTION_DEFAULT 22 // default correction for sensor error in yaw
|
||||
#define PROXIMITY_MAX_IGNORE 6 // up to six areas can be ignored
|
||||
#define PROXIMITY_MAX_DIRECTION 8
|
||||
#define PROXIMITY_SENSOR_ID_START 10
|
||||
|
|
Loading…
Reference in New Issue