mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Rover: removed SONAR_TYPE option
now set the values in the object
This commit is contained in:
parent
d0f27f8830
commit
6dd549dea8
@ -99,7 +99,6 @@ public:
|
||||
// obstacle control
|
||||
k_param_sonar_enabled = 190,
|
||||
k_param_sonar, // sonar object
|
||||
k_param_sonar_type,
|
||||
k_param_sonar_trigger_cm,
|
||||
k_param_sonar_turn_angle,
|
||||
k_param_sonar_turn_time,
|
||||
@ -204,8 +203,6 @@ public:
|
||||
|
||||
// obstacle control
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m
|
||||
// range), // 3 = HRLV
|
||||
AP_Int16 sonar_trigger_cm;
|
||||
AP_Float sonar_turn_angle;
|
||||
AP_Float sonar_turn_time;
|
||||
|
@ -282,11 +282,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @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),
|
||||
|
||||
|
||||
// @Param: MODE_CH
|
||||
// @DisplayName: Mode channel
|
||||
// @Description: RC Channel to use for driving mode control
|
||||
|
Loading…
Reference in New Issue
Block a user