mirror of https://github.com/ArduPilot/ardupilot
Added Michael Pursifull's Maxsonar HRLV model support
This commit is contained in:
parent
7a5544051d
commit
d4a0cb5db1
|
@ -336,7 +336,9 @@ public:
|
|||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m range)
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV,
|
||||
// 2 = XLL (XL with 10m range)
|
||||
// 3 = HRLV
|
||||
#endif
|
||||
#endif
|
||||
AP_Int8 airspeed_enabled;
|
||||
|
|
|
@ -210,7 +210,9 @@ public:
|
|||
|
||||
AP_Int16 RTL_altitude;
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m range)
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV,
|
||||
// 2 = XLL (XL with 10m range)
|
||||
// 3 = HRLV
|
||||
AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current
|
||||
AP_Float volt_div_ratio;
|
||||
AP_Float curr_amp_per_volt;
|
||||
|
|
|
@ -431,12 +431,12 @@ setup_sonar(uint8_t argc, const Menu::arg *argv)
|
|||
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
|
||||
g.sonar_enabled.set_and_save(false);
|
||||
|
||||
} else if (argc > 1 && (argv[1].i >= 0 && argv[1].i <= 2)) {
|
||||
} else if (argc > 1 && (argv[1].i >= 0 && argv[1].i <= 3)) {
|
||||
g.sonar_enabled.set_and_save(true); // if you set the sonar type, surely you want it on
|
||||
g.sonar_type.set_and_save(argv[1].i);
|
||||
|
||||
}else{
|
||||
Serial.printf_P(PSTR("\nOp:[on, off, 0-2]\n"));
|
||||
Serial.printf_P(PSTR("\nOp:[on, off, 0-3]\n"));
|
||||
report_sonar();
|
||||
return 0;
|
||||
}
|
||||
|
@ -824,7 +824,7 @@ static void report_sonar()
|
|||
Serial.printf_P(PSTR("Sonar\n"));
|
||||
print_divider();
|
||||
print_enabled(g.sonar_enabled.get());
|
||||
Serial.printf_P(PSTR("Type: %d (0=XL, 1=LV, 2=XLL)"), (int)g.sonar_type);
|
||||
Serial.printf_P(PSTR("Type: %d (0=XL, 1=LV, 2=XLL, 3=HRLV)"), (int)g.sonar_type);
|
||||
print_blanks(2);
|
||||
}
|
||||
|
||||
|
|
|
@ -63,6 +63,11 @@ float AP_RangeFinder_MaxsonarXL::calculate_scaler(int sonar_type, float adc_refe
|
|||
min_distance = AP_RANGEFINDER_MAXSONARXLL_MIN_DISTANCE;
|
||||
max_distance = AP_RANGEFINDER_MAXSONARXLL_MAX_DISTANCE;
|
||||
break;
|
||||
case AP_RANGEFINDER_MAXSONARHRLV:
|
||||
type_scaler = AP_RANGEFINDER_MAXSONARHRLV_SCALER;
|
||||
min_distance = AP_RANGEFINDER_MAXSONARHRLV_MIN_DISTANCE;
|
||||
max_distance = AP_RANGEFINDER_MAXSONARHRLV_MAX_DISTANCE;
|
||||
break;
|
||||
}
|
||||
_scaler = type_scaler * adc_refence_voltage / 5.0;
|
||||
return _scaler;
|
||||
|
|
|
@ -21,6 +21,12 @@
|
|||
#define AP_RANGEFINDER_MAXSONARXLL_MIN_DISTANCE 20
|
||||
#define AP_RANGEFINDER_MAXSONARXLL_MAX_DISTANCE 1068
|
||||
|
||||
// HRLV-MaxSonar-EZ0 (aka HRLV)
|
||||
#define AP_RANGEFINDER_MAXSONARHRLV 3
|
||||
#define AP_RANGEFINDER_MAXSONARHRLV_SCALER 0.512
|
||||
#define AP_RANGEFINDER_MAXSONARHRLV_MIN_DISTANCE 30
|
||||
#define AP_RANGEFINDER_MAXSONARHRLV_MAX_DISTANCE 500
|
||||
|
||||
class AP_RangeFinder_MaxsonarXL : public RangeFinder
|
||||
{
|
||||
public:
|
||||
|
|
Loading…
Reference in New Issue