Plane: use enum-class for RangeFinder Status
This commit is contained in:
parent
dfc8349866
commit
6cd4dfba2c
@ -195,7 +195,7 @@ struct PACKED log_Sonar {
|
|||||||
void Plane::Log_Write_Sonar()
|
void Plane::Log_Write_Sonar()
|
||||||
{
|
{
|
||||||
uint16_t distance = 0;
|
uint16_t distance = 0;
|
||||||
if (rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) {
|
if (rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) {
|
||||||
distance = rangefinder.distance_cm_orient(ROTATION_PITCH_270);
|
distance = rangefinder.distance_cm_orient(ROTATION_PITCH_270);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -129,7 +129,7 @@ float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (use_rangefinder_if_available && quadplane.in_vtol_land_final() &&
|
if (use_rangefinder_if_available && quadplane.in_vtol_land_final() &&
|
||||||
rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_OutOfRangeLow) {
|
rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow) {
|
||||||
// a special case for quadplane landing when rangefinder goes
|
// a special case for quadplane landing when rangefinder goes
|
||||||
// below minimum. Consider our height above ground to be zero
|
// below minimum. Consider our height above ground to be zero
|
||||||
return 0;
|
return 0;
|
||||||
@ -613,7 +613,7 @@ void Plane::rangefinder_height_update(void)
|
|||||||
{
|
{
|
||||||
float distance = rangefinder.distance_cm_orient(ROTATION_PITCH_270)*0.01f;
|
float distance = rangefinder.distance_cm_orient(ROTATION_PITCH_270)*0.01f;
|
||||||
|
|
||||||
if ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && ahrs.home_is_set()) {
|
if ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) && ahrs.home_is_set()) {
|
||||||
if (!rangefinder_state.have_initial_reading) {
|
if (!rangefinder_state.have_initial_reading) {
|
||||||
rangefinder_state.have_initial_reading = true;
|
rangefinder_state.have_initial_reading = true;
|
||||||
rangefinder_state.initial_range = distance;
|
rangefinder_state.initial_range = distance;
|
||||||
|
Loading…
Reference in New Issue
Block a user