AP_RangeFinder: move some backend implementations to cpp file

This commit is contained in:
Randy Mackay 2018-08-27 15:11:09 +09:00
parent 9a7b378ddd
commit 9e27b93538
2 changed files with 24 additions and 17 deletions

View File

@ -30,6 +30,27 @@ AP_RangeFinder_Backend::AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_
_sem = hal.util->new_semaphore(); _sem = hal.util->new_semaphore();
} }
MAV_DISTANCE_SENSOR AP_RangeFinder_Backend::get_mav_distance_sensor_type() const {
if (state.type == RangeFinder::RangeFinder_TYPE_NONE) {
return MAV_DISTANCE_SENSOR_UNKNOWN;
}
return _get_mav_distance_sensor_type();
}
RangeFinder::RangeFinder_Status AP_RangeFinder_Backend::status() const {
if (state.type == RangeFinder::RangeFinder_TYPE_NONE) {
// turned off at runtime?
return RangeFinder::RangeFinder_NotConnected;
}
return state.status;
}
// true if sensor is returning data
bool AP_RangeFinder_Backend::has_data() const {
return ((state.status != RangeFinder::RangeFinder_NotConnected) &&
(state.status != RangeFinder::RangeFinder_NoData));
}
// update status based on distance measurement // update status based on distance measurement
void AP_RangeFinder_Backend::update_status() void AP_RangeFinder_Backend::update_status()
{ {

View File

@ -41,26 +41,12 @@ public:
int16_t max_distance_cm() const { return state.max_distance_cm; } int16_t max_distance_cm() const { return state.max_distance_cm; }
int16_t min_distance_cm() const { return state.min_distance_cm; } int16_t min_distance_cm() const { return state.min_distance_cm; }
int16_t ground_clearance_cm() const { return state.ground_clearance_cm; } int16_t ground_clearance_cm() const { return state.ground_clearance_cm; }
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const { MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const;
if (state.type == RangeFinder::RangeFinder_TYPE_NONE) { RangeFinder::RangeFinder_Status status() const;
return MAV_DISTANCE_SENSOR_UNKNOWN;
}
return _get_mav_distance_sensor_type();
}
RangeFinder::RangeFinder_Status status() const {
if (state.type == RangeFinder::RangeFinder_TYPE_NONE) {
// turned off at runtime?
return RangeFinder::RangeFinder_NotConnected;
}
return state.status;
}
RangeFinder::RangeFinder_Type type() const { return (RangeFinder::RangeFinder_Type)state.type.get(); } RangeFinder::RangeFinder_Type type() const { return (RangeFinder::RangeFinder_Type)state.type.get(); }
// true if sensor is returning data // true if sensor is returning data
bool has_data() const { bool has_data() const;
return ((state.status != RangeFinder::RangeFinder_NotConnected) &&
(state.status != RangeFinder::RangeFinder_NoData));
}
// returns count of consecutive good readings // returns count of consecutive good readings
uint8_t range_valid_count() const { return state.range_valid_count; } uint8_t range_valid_count() const { return state.range_valid_count; }