Rover: cleaned up sonar_trigger_cm parameter

This commit is contained in:
Andrew Tridgell 2013-03-01 07:47:26 +11:00
parent 4de635aa48
commit be3b2ee9f8
2 changed files with 3 additions and 5 deletions

View File

@ -669,7 +669,7 @@ static void fast_loop()
// ----------
if (g.sonar_enabled) {
sonar_dist_cm = sonar->read();
if (sonar_dist_cm <= g.sonar_trigger) {
if (sonar_dist_cm <= g.sonar_trigger_cm) {
// obstacle detected in front
obstacle = true;
} else {

View File

@ -17,7 +17,7 @@ public:
// The increment will prevent old parameters from being used incorrectly
// by newer code.
//
static const uint16_t k_format_version = 15;
static const uint16_t k_format_version = 16;
static const uint16_t k_software_type = 20;
enum {
@ -97,8 +97,7 @@ public:
k_param_fs_gcs_enabled,
// obstacle control
k_param_sonar_trigger = 190,
k_param_sonar_enabled,
k_param_sonar_enabled = 190,
k_param_sonar_type,
k_param_sonar_trigger_cm,
k_param_sonar_turn_angle,
@ -203,7 +202,6 @@ public:
AP_Int8 fs_gcs_enabled;
// obstacle control
AP_Float sonar_trigger;
AP_Int8 sonar_enabled;
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m
// range), // 3 = HRLV