mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: added more sonar parameters
better control over obstacle avoidance
This commit is contained in:
parent
06dd6c2790
commit
66abee5544
@ -100,6 +100,9 @@ public:
|
||||
k_param_sonar_trigger = 190,
|
||||
k_param_sonar_enabled,
|
||||
k_param_sonar_type,
|
||||
k_param_sonar_trigger_cm,
|
||||
k_param_sonar_turn_angle,
|
||||
k_param_sonar_turn_time,
|
||||
|
||||
//
|
||||
// 210: driving modes
|
||||
@ -203,8 +206,11 @@ public:
|
||||
AP_Float sonar_trigger;
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m
|
||||
// range),
|
||||
// 3 = HRLV
|
||||
// range), // 3 = HRLV
|
||||
AP_Int16 sonar_trigger_cm;
|
||||
AP_Float sonar_turn_angle;
|
||||
AP_Float sonar_turn_time;
|
||||
|
||||
|
||||
// driving modes
|
||||
//
|
||||
|
@ -248,16 +248,43 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", 0),
|
||||
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
// @Param: SONAR_ENABLE
|
||||
// @DisplayName: Enable Sonar
|
||||
// @Description: Setting this to Enabled(1) will enable the sonar. Setting this to Disabled(0) will disable the sonar
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_trigger, "SONAR_TRIGGER", SONAR_TRIGGER),
|
||||
GSCALAR(sonar_enabled, "SONAR_ENABLE", SONAR_ENABLED),
|
||||
|
||||
// @Param: SONAR_TRIGGER_CM
|
||||
// @DisplayName: Sonar trigger distance
|
||||
// @Description: The distance from an obstacle at which the sonar triggers a turn to avoid the obstacle
|
||||
// @Units: centimeters
|
||||
// @Range: 0 1000
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_trigger_cm, "SONAR_TRIGGER_CM", 100),
|
||||
|
||||
// @Param: SONAR_TURN_ANGLE
|
||||
// @DisplayName: Sonar trigger angle
|
||||
// @Description: The course deviation in degrees to apply while avoiding an obstacle detected with the sonar. A positive number means to turn right, and a negative angle means to turn left.
|
||||
// @Units: centimeters
|
||||
// @Range: 0 90
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_turn_angle, "SONAR_TURN_ANGLE", 45),
|
||||
|
||||
// @Param: SONAR_TURN_TIME
|
||||
// @DisplayName: Sonar turn time
|
||||
// @Description: The amount of time in seconds to apply the SONAR_TURN_ANGLE after detecting an obstacle.
|
||||
// @Units: seconds
|
||||
// @Range: 0 100
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_turn_time, "SONAR_TURN_TIME", 2.0f),
|
||||
|
||||
|
||||
// add sonar scaling, min, max params
|
||||
GSCALAR(sonar_type, "SONAR_TYPE", AP_RANGEFINDER_MAXSONARXL),
|
||||
#endif
|
||||
|
||||
|
||||
// @Param: MODE_CH
|
||||
|
Loading…
Reference in New Issue
Block a user