APM:Libraries
RangeFinder.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 <AP_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
22 
23 // Maximum number of range finder instances available on this platform
24 #define RANGEFINDER_MAX_INSTANCES 2
25 #define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT 10
26 #define RANGEFINDER_PREARM_ALT_MAX_CM 200
27 #define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50
28 
30 
32 {
33  friend class AP_RangeFinder_Backend;
34 
35 public:
36  RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default);
37 
38  /* Do not allow copies */
39  RangeFinder(const RangeFinder &other) = delete;
40  RangeFinder &operator=(const RangeFinder&) = delete;
41 
42  // RangeFinder driver types
65  };
66 
71  };
72 
79  };
80 
81  // The RangeFinder_State structure is filled in by the backend driver
83  uint16_t distance_cm; // distance: in cm
84  uint16_t voltage_mv; // voltage in millivolts,
85  // if applicable, otherwise 0
86  enum RangeFinder_Status status; // sensor status
87  uint8_t range_valid_count; // number of consecutive valid readings (maxes out at 10)
88  bool pre_arm_check; // true if sensor has passed pre-arm checks
89  uint16_t pre_arm_distance_min; // min distance captured during pre-arm checks
90  uint16_t pre_arm_distance_max; // max distance captured during pre-arm checks
91 
92  AP_Int8 type;
93  AP_Int8 pin;
94  AP_Int8 ratiometric;
95  AP_Int8 stop_pin;
96  AP_Int16 settle_time_ms;
97  AP_Float scaling;
98  AP_Float offset;
99  AP_Int8 function;
100  AP_Int16 min_distance_cm;
101  AP_Int16 max_distance_cm;
103  AP_Int8 address;
104  AP_Vector3f pos_offset; // position offset in body frame
105  AP_Int8 orientation;
107  };
108 
110 
112 
113  // parameters for each instance
114  static const struct AP_Param::GroupInfo var_info[];
115 
116  // Return the number of range finder instances
117  uint8_t num_sensors(void) const {
118  return num_instances;
119  }
120 
121  // detect and initialise any available rangefinders
122  void init(void);
123 
124  // update state of all rangefinders. Should be called at around
125  // 10Hz from main loop
126  void update(void);
127 
128  // Handle an incoming DISTANCE_SENSOR message (from a MAVLink enabled range finder)
129  void handle_msg(mavlink_message_t *msg);
130 
131  // return true if we have a range finder with the specified orientation
132  bool has_orientation(enum Rotation orientation) const;
133 
134  // find first range finder instance with the specified orientation
135  AP_RangeFinder_Backend *find_instance(enum Rotation orientation) const;
136 
137  AP_RangeFinder_Backend *get_backend(uint8_t id) const;
138 
139  // methods to return a distance on a particular orientation from
140  // any sensor which can current supply it
141  uint16_t distance_cm_orient(enum Rotation orientation) const;
142  uint16_t voltage_mv_orient(enum Rotation orientation) const;
143  int16_t max_distance_cm_orient(enum Rotation orientation) const;
144  int16_t min_distance_cm_orient(enum Rotation orientation) const;
145  int16_t ground_clearance_cm_orient(enum Rotation orientation) const;
146  MAV_DISTANCE_SENSOR get_mav_distance_sensor_type_orient(enum Rotation orientation) const;
147  RangeFinder_Status status_orient(enum Rotation orientation) const;
148  bool has_data_orient(enum Rotation orientation) const;
149  uint8_t range_valid_count_orient(enum Rotation orientation) const;
150  const Vector3f &get_pos_offset_orient(enum Rotation orientation) const;
151 
152  /*
153  set an externally estimated terrain height. Used to enable power
154  saving (where available) at high altitudes.
155  */
156  void set_estimated_terrain_height(float height) {
157  estimated_terrain_height = height;
158  }
159 
160  /*
161  returns true if pre-arm checks have passed for all range finders
162  these checks involve the user lifting or rotating the vehicle so that sensor readings between
163  the min and 2m can be captured
164  */
165  bool pre_arm_check() const;
166 
167  static RangeFinder *get_singleton(void) { return _singleton; }
168 
169 
170 private:
172 
175  uint8_t num_instances:3;
178  Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
179 
180  void detect_instance(uint8_t instance, uint8_t& serial_instance);
181  void update_instance(uint8_t instance);
182 
183  bool _add_backend(AP_RangeFinder_Backend *driver);
184 };
AP_RangeFinder_Backend * get_backend(uint8_t id) const
bool has_data_orient(enum Rotation orientation) const
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type_orient(enum Rotation orientation) const
static RangeFinder * _singleton
Definition: RangeFinder.h:171
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES]
Definition: RangeFinder.h:173
void update(void)
AP_SerialManager & serial_manager
Definition: RangeFinder.h:177
const Vector3f & get_pos_offset_orient(enum Rotation orientation) const
#define RANGEFINDER_MAX_INSTANCES
Definition: RangeFinder.h:24
RangeFinder & operator=(const RangeFinder &)=delete
static RangeFinder * get_singleton(void)
Definition: RangeFinder.h:167
bool has_orientation(enum Rotation orientation) const
float estimated_terrain_height
Definition: RangeFinder.h:176
AP_RangeFinder_Backend * find_instance(enum Rotation orientation) const
uint8_t range_valid_count_orient(enum Rotation orientation) const
void set_estimated_terrain_height(float height)
Definition: RangeFinder.h:156
void update_instance(uint8_t instance)
uint8_t num_sensors(void) const
Definition: RangeFinder.h:117
Rotation
Definition: rotations.h:27
enum RangeFinder_Status status
Definition: RangeFinder.h:86
A system for managing and storing variables that are of general interest to the system.
void detect_instance(uint8_t instance, uint8_t &serial_instance)
uint8_t num_instances
Definition: RangeFinder.h:175
AP_Int16 _powersave_range
Definition: RangeFinder.h:111
uint16_t distance_cm_orient(enum Rotation orientation) const
int16_t max_distance_cm_orient(enum Rotation orientation) const
bool _add_backend(AP_RangeFinder_Backend *driver)
AP_RangeFinder_Backend * drivers[RANGEFINDER_MAX_INSTANCES]
Definition: RangeFinder.h:174
Vector3f pos_offset_zero
Definition: RangeFinder.h:178
uint16_t voltage_mv_orient(enum Rotation orientation) const
Common definitions and utility routines for the ArduPilot libraries.
void handle_msg(mavlink_message_t *msg)
RangeFinder_Status status_orient(enum Rotation orientation) const
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default)
const struct AP_Param::GroupInfo * var_info
Definition: RangeFinder.h:106
static const struct AP_Param::GroupInfo * backend_var_info[RANGEFINDER_MAX_INSTANCES]
Definition: RangeFinder.h:109
void init(void)
int16_t ground_clearance_cm_orient(enum Rotation orientation) const
int16_t min_distance_cm_orient(enum Rotation orientation) const