APM:Libraries
RangeFinder_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include "RangeFinder.h"
20 
22 {
23 public:
24  // constructor. This incorporates initialisation as well.
26 
27  // we declare a virtual destructor so that RangeFinder drivers can
28  // override with a custom destructor if need be
29  virtual ~AP_RangeFinder_Backend(void) {}
30 
31  // update the state structure
32  virtual void update() = 0;
33 
34  virtual void handle_msg(mavlink_message_t *msg) { return; }
35 
36  void update_pre_arm_check();
37 
38  enum Rotation orientation() const { return (Rotation)state.orientation.get(); }
39  uint16_t distance_cm() const { return state.distance_cm; }
40  uint16_t voltage_mv() const { return state.voltage_mv; }
41  int16_t max_distance_cm() const { return state.max_distance_cm; }
42  int16_t min_distance_cm() const { return state.min_distance_cm; }
43  int16_t ground_clearance_cm() const { return state.ground_clearance_cm; }
44  MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const {
46  return MAV_DISTANCE_SENSOR_UNKNOWN;
47  }
49  }
52  // turned off at runtime?
54  }
55  return state.status;
56  }
58 
59  // true if sensor is returning data
60  bool has_data() const {
63  }
64 
65  // returns count of consecutive good readings
66  uint8_t range_valid_count() const { return state.range_valid_count; }
67 
68  // return a 3D vector defining the position offset of the sensor
69  // in metres relative to the body frame origin
70  const Vector3f &get_pos_offset() const { return state.pos_offset; }
71 
72 protected:
73 
74  // update status based on distance measurement
75  void update_status();
76 
77  // set status and update valid_count
79 
81 
82  // semaphore for access to shared frontend data
84 
85  virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0;
86 };
uint16_t voltage_mv() const
RangeFinder::RangeFinder_Type type() const
enum Rotation orientation() const
uint16_t distance_cm() const
int16_t ground_clearance_cm() const
AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state)
virtual void handle_msg(mavlink_message_t *msg)
Rotation
Definition: rotations.h:27
const Vector3f & get_pos_offset() const
AP_HAL::Semaphore * _sem
enum RangeFinder_Status status
Definition: RangeFinder.h:86
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const =0
virtual ~AP_RangeFinder_Backend(void)
uint8_t range_valid_count() const
virtual void update()=0
Common definitions and utility routines for the ArduPilot libraries.
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_Status status() const
int16_t min_distance_cm() const
RangeFinder::RangeFinder_State & state
int16_t max_distance_cm() const