APM:Libraries
IRLock.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 
16 /*
17  * IRLock.h - IRLock Base Class for Ardupilot
18  *
19  * Created on: Nov 10, 2014
20  * Author: MLandes
21  */
22 #pragma once
23 
24 #include <AP_AHRS/AP_AHRS.h>
25 
26 class IRLock
27 {
28 public:
29  // init - initialize sensor library
30  // library won't be useable unless this is first called
31  virtual void init(int8_t bus) = 0;
32 
33  // true if irlock sensor is online and healthy
34  bool healthy() const { return _flags.healthy; }
35 
36  // timestamp of most recent data read from the sensor
37  uint32_t last_update_ms() const { return _last_update_ms; }
38 
39  // returns the number of blocks in the current frame
40  size_t num_targets() const { return _flags.healthy?1:0; }
41 
42  // retrieve latest sensor data - returns true if new data is available
43  virtual bool update() = 0;
44 
45  // retrieve body frame x and y angles (in radians) to target
46  // returns true if data is available
47  bool get_angle_to_target_rad(float &x_angle_rad, float &y_angle_rad) const;
48 
49  // retrieve body frame unit vector in direction of target
50  // returns true if data is available
51  bool get_unit_vector_body(Vector3f& ret) const;
52 
53 
54 protected:
55  struct AP_IRLock_Flags {
56  uint8_t healthy : 1; // true if sensor is healthy
57  } _flags;
58 
59  // internals
60  uint32_t _last_update_ms;
61 
62  // irlock_target_info is a duplicate of the PX4Firmware irlock_s structure
63  typedef struct {
64  uint32_t timestamp; // milliseconds since system start
65  float pos_x; // x-axis distance from center of image to center of target in units of tan(theta)
66  float pos_y; // y-axis distance from center of image to center of target in units of tan(theta)
67  float size_x; // size of target along x-axis in units of tan(theta)
68  float size_y; // size of target along y-axis in units of tan(theta)
70 
72 };
uint32_t last_update_ms() const
Definition: IRLock.h:37
bool get_unit_vector_body(Vector3f &ret) const
Definition: IRLock.cpp:27
virtual bool update()=0
irlock_target_info _target_info
Definition: IRLock.h:71
size_t num_targets() const
Definition: IRLock.h:40
bool get_angle_to_target_rad(float &x_angle_rad, float &y_angle_rad) const
Definition: IRLock.cpp:12
Definition: IRLock.h:26
bool healthy() const
Definition: IRLock.h:34
virtual void init(int8_t bus)=0
uint32_t _last_update_ms
Definition: IRLock.h:60
struct IRLock::AP_IRLock_Flags _flags