Browse Source

Ardurover2 Parameters: Changed the SONAR prefix to RNGFND and renamed the previous SONAR_ parameters

master
akdslr 11 years ago committed by Andrew Tridgell
parent
commit
1083a89b0f
  1. 36
      APMrover2/Parameters.pde

36
APMrover2/Parameters.pde

@ -327,40 +327,40 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -327,40 +327,40 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", 0),
// @Param: SONAR_TRIGGER_CM
// @DisplayName: Sonar trigger distance
// @Description: The distance from an obstacle in centimeters at which the sonar triggers a turn to avoid the obstacle
// @Param: RNGFND_TRIGGR_CM
// @DisplayName: Rangefinder trigger distance
// @Description: The distance from an obstacle in centimeters at which the rangefinder triggers a turn to avoid the obstacle
// @Units: centimeters
// @Range: 0 1000
// @Increment: 1
// @User: Standard
GSCALAR(sonar_trigger_cm, "SONAR_TRIGGER_CM", 100),
GSCALAR(sonar_trigger_cm, "RNGFND_TRIGGR_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.
// @Param: RNGFND_TURN_ANGL
// @DisplayName: Rangefinder trigger angle
// @Description: The course deviation in degrees to apply while avoiding an obstacle detected with the rangefinder. A positive number means to turn right, and a negative angle means to turn left.
// @Units: centimeters
// @Range: -45 45
// @Increment: 1
// @User: Standard
GSCALAR(sonar_turn_angle, "SONAR_TURN_ANGLE", 45),
GSCALAR(sonar_turn_angle, "RNGFND_TURN_ANGL", 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.
// @Param: RNGFND_TURN_TIME
// @DisplayName: Rangefinder turn time
// @Description: The amount of time in seconds to apply the RNGFND_TURN_ANGL after detecting an obstacle.
// @Units: seconds
// @Range: 0 100
// @Increment: 0.1
// @User: Standard
GSCALAR(sonar_turn_time, "SONAR_TURN_TIME", 1.0f),
GSCALAR(sonar_turn_time, "RNGFND_TURN_TIME", 1.0f),
// @Param: SONAR_DEBOUNCE
// @DisplayName: Sonar debounce count
// @Description: The number of 50Hz sonar hits needed to trigger an obstacle avoidance event. If you get a lot of false sonar events then raise this number, but if you make it too large then it will cause lag in detecting obstacles, which could cause you go hit the obstacle.
// @Param: RNGFND_DEBOUNCE
// @DisplayName: Rangefinder debounce count
// @Description: The number of 50Hz rangefinder hits needed to trigger an obstacle avoidance event. If you get a lot of false sonar events then raise this number, but if you make it too large then it will cause lag in detecting obstacles, which could cause you go hit the obstacle.
// @Range: 1 100
// @Increment: 1
// @User: Standard
GSCALAR(sonar_debounce, "SONAR_DEBOUNCE", 2),
GSCALAR(sonar_debounce, "RNGFND_DEBOUNCE", 2),
// @Param: LEARN_CH
// @DisplayName: Learning channel
@ -482,9 +482,9 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -482,9 +482,9 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AP_L1_Control/AP_L1_Control.cpp
GOBJECT(L1_controller, "NAVL1_", AP_L1_Control),
// @Group: SONAR
// @Group: RNGFND
// @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
GOBJECT(sonar, "SONAR", RangeFinder),
GOBJECT(sonar, "RNGFND", RangeFinder),
// @Group: INS_
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp

Loading…
Cancel
Save