ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

67 lines
1.8 KiB
C
Raw Normal View History

2018-08-29 11:18:49 -03:00
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_PWM_ENABLED
#include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.h"
2018-08-29 11:18:49 -03:00
class AP_RangeFinder_PWM : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_PWM(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
float &_estimated_terrain_height);
2018-08-29 11:18:49 -03:00
// destructor
~AP_RangeFinder_PWM(void) {};
// static detection function
static bool detect();
// update state
void update(void) override;
2018-08-29 11:18:49 -03:00
protected:
bool get_reading(float &reading_m);
2018-08-29 11:18:49 -03:00
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return MAV_DISTANCE_SENSOR_UNKNOWN;
}
private:
bool check_pin();
void check_stop_pin();
bool check_pins();
uint8_t last_stop_pin = -1;
AP_HAL::PWMSource pwm_source;
float &estimated_terrain_height;
// return true if we are beyond the power saving range
bool out_of_range(void) const;
bool was_out_of_range = -1; // this odd initialisation ensures we transition to new state
2018-08-29 11:18:49 -03:00
};
#endif // AP_RANGEFINDER_PWM_ENABLED