Rover: use new sonar enabled flag in object
This commit is contained in:
parent
91bbf914f7
commit
065cac76c0
@ -624,7 +624,7 @@ static void fast_loop()
|
|||||||
|
|
||||||
// Read Sonar
|
// Read Sonar
|
||||||
// ----------
|
// ----------
|
||||||
if (g.sonar_enabled) {
|
if (sonar.enabled()) {
|
||||||
float sonar_dist_cm = sonar.distance_cm();
|
float sonar_dist_cm = sonar.distance_cm();
|
||||||
if (sonar_dist_cm <= g.sonar_trigger_cm) {
|
if (sonar_dist_cm <= g.sonar_trigger_cm) {
|
||||||
// obstacle detected in front
|
// obstacle detected in front
|
||||||
|
@ -99,7 +99,7 @@ public:
|
|||||||
k_param_fs_gcs_enabled,
|
k_param_fs_gcs_enabled,
|
||||||
|
|
||||||
// obstacle control
|
// obstacle control
|
||||||
k_param_sonar_enabled = 190,
|
k_param_sonar_enabled = 190, // deprecated, can be removed
|
||||||
k_param_sonar, // sonar object
|
k_param_sonar, // sonar object
|
||||||
k_param_sonar_trigger_cm,
|
k_param_sonar_trigger_cm,
|
||||||
k_param_sonar_turn_angle,
|
k_param_sonar_turn_angle,
|
||||||
@ -205,7 +205,6 @@ public:
|
|||||||
AP_Int8 fs_gcs_enabled;
|
AP_Int8 fs_gcs_enabled;
|
||||||
|
|
||||||
// obstacle control
|
// obstacle control
|
||||||
AP_Int8 sonar_enabled;
|
|
||||||
AP_Int16 sonar_trigger_cm;
|
AP_Int16 sonar_trigger_cm;
|
||||||
AP_Float sonar_turn_angle;
|
AP_Float sonar_turn_angle;
|
||||||
AP_Float sonar_turn_time;
|
AP_Float sonar_turn_time;
|
||||||
|
@ -256,13 +256,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", 0),
|
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", 0),
|
||||||
|
|
||||||
// @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_enabled, "SONAR_ENABLE", SONAR_ENABLED),
|
|
||||||
|
|
||||||
// @Param: SONAR_TRIGGER_CM
|
// @Param: SONAR_TRIGGER_CM
|
||||||
// @DisplayName: Sonar trigger distance
|
// @DisplayName: Sonar trigger distance
|
||||||
// @Description: The distance from an obstacle at which the sonar triggers a turn to avoid the obstacle
|
// @Description: The distance from an obstacle at which the sonar triggers a turn to avoid the obstacle
|
||||||
|
@ -550,7 +550,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
|||||||
static int8_t
|
static int8_t
|
||||||
test_sonar(uint8_t argc, const Menu::arg *argv)
|
test_sonar(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
if (!g.sonar_enabled) {
|
if (!sonar.enabled()) {
|
||||||
cliSerial->println_P(PSTR("WARNING: Sonar is not enabled"));
|
cliSerial->println_P(PSTR("WARNING: Sonar is not enabled"));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user