mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Sub: use enum-class for RangeFinder Status
This commit is contained in:
parent
6cd4dfba2c
commit
b3f1fdf182
@ -626,12 +626,12 @@ bool Sub::auto_terrain_recover_start()
|
|||||||
// Check rangefinder status to see if recovery is possible
|
// Check rangefinder status to see if recovery is possible
|
||||||
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
|
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
|
||||||
|
|
||||||
case RangeFinder::RangeFinder_OutOfRangeLow:
|
case RangeFinder::Status::OutOfRangeLow:
|
||||||
case RangeFinder::RangeFinder_OutOfRangeHigh:
|
case RangeFinder::Status::OutOfRangeHigh:
|
||||||
|
|
||||||
// RangeFinder_Good if just one valid sample was obtained recently, but ::rangefinder_state.alt_healthy
|
// RangeFinder::Good if just one valid sample was obtained recently, but ::rangefinder_state.alt_healthy
|
||||||
// requires several consecutive valid readings for wpnav to accept rangefinder data
|
// requires several consecutive valid readings for wpnav to accept rangefinder data
|
||||||
case RangeFinder::RangeFinder_Good:
|
case RangeFinder::Status::Good:
|
||||||
auto_mode = Auto_TerrainRecover;
|
auto_mode = Auto_TerrainRecover;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -683,17 +683,17 @@ void Sub::auto_terrain_recover_run()
|
|||||||
|
|
||||||
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
|
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
|
||||||
|
|
||||||
case RangeFinder::RangeFinder_OutOfRangeLow:
|
case RangeFinder::Status::OutOfRangeLow:
|
||||||
target_climb_rate = wp_nav.get_default_speed_up();
|
target_climb_rate = wp_nav.get_default_speed_up();
|
||||||
rangefinder_recovery_ms = 0;
|
rangefinder_recovery_ms = 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case RangeFinder::RangeFinder_OutOfRangeHigh:
|
case RangeFinder::Status::OutOfRangeHigh:
|
||||||
target_climb_rate = wp_nav.get_default_speed_down();
|
target_climb_rate = wp_nav.get_default_speed_down();
|
||||||
rangefinder_recovery_ms = 0;
|
rangefinder_recovery_ms = 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case RangeFinder::RangeFinder_Good: // exit on success (recovered rangefinder data)
|
case RangeFinder::Status::Good: // exit on success (recovered rangefinder data)
|
||||||
|
|
||||||
target_climb_rate = 0; // Attempt to hold current depth
|
target_climb_rate = 0; // Attempt to hold current depth
|
||||||
|
|
||||||
|
@ -30,7 +30,7 @@ void Sub::read_rangefinder()
|
|||||||
#if RANGEFINDER_ENABLED == ENABLED
|
#if RANGEFINDER_ENABLED == ENABLED
|
||||||
rangefinder.update();
|
rangefinder.update();
|
||||||
|
|
||||||
rangefinder_state.alt_healthy = ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && (rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX));
|
rangefinder_state.alt_healthy = ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) && (rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX));
|
||||||
|
|
||||||
int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270);
|
int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user