APM:Libraries
AP_IRLock_I2C.cpp
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  * AP_IRLock_I2C.cpp
18  *
19  * Based on AP_IRLock_PX4 by MLandes
20  *
21  * See: http://irlock.com/pages/serial-communication-protocol
22  */
23 #include <AP_HAL/AP_HAL.h>
24 #include "AP_IRLock_I2C.h"
25 #include <stdio.h>
26 #include <utility>
27 #include <AP_HAL/I2CDevice.h>
28 
29 extern const AP_HAL::HAL& hal;
30 
31 #define IRLOCK_I2C_ADDRESS 0x54
32 
33 #define IRLOCK_SYNC 0xAA55AA55
34 
35 void AP_IRLock_I2C::init(int8_t bus)
36 {
37  if (bus < 0) {
38  // default to i2c external bus
39  bus = 1;
40  }
41  dev = std::move(hal.i2c_mgr->get_device(bus, IRLOCK_I2C_ADDRESS));
42  if (!dev) {
43  return;
44  }
45 
46  sem = hal.util->new_semaphore();
47 
48  // read at 50Hz
49  printf("Starting IRLock on I2C\n");
50 
52 }
53 
54 /*
55  synchronise with frame start. We expect 0xAA55AA55 at the start of
56  a frame
57 */
59 {
60  uint32_t sync_word;
61  if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) {
62  return false;
63  }
64 
65  // record sensor successfully responded to I2C request
67 
68  uint8_t count=40;
69  while (count-- && sync_word != IRLOCK_SYNC && sync_word != 0) {
70  uint8_t sync_byte;
71  if (!dev->transfer(nullptr, 0, &sync_byte, 1)) {
72  return false;
73  }
74  if (sync_byte == 0) {
75  break;
76  }
77  sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24);
78  }
79  return sync_word == IRLOCK_SYNC;
80 }
81 
82 /*
83  converts IRLOCK pixels to a position on a normal plane 1m in front of the lens
84  based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed
85  */
86 void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y)
87 {
88  ret_x = (-0.00293875727162397f*pix_x + 0.470201163459835f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) +
89  4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f);
90  ret_y = (-0.003056843086277f*pix_y + 0.3056843086277f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) +
91  4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f);
92 }
93 
94 /*
95  read a frame from sensor
96 */
97 bool AP_IRLock_I2C::read_block(struct frame &irframe)
98 {
99  if (!dev->transfer(nullptr, 0, (uint8_t*)&irframe, sizeof(irframe))) {
100  return false;
101  }
102 
103  // record sensor successfully responded to I2C request
105 
106  /* check crc */
107  uint32_t crc = irframe.signature + irframe.pixel_x + irframe.pixel_y + irframe.pixel_size_x + irframe.pixel_size_y;
108  if (crc != irframe.checksum) {
109  // printf("bad crc 0x%04x 0x%04x\n", crc, irframe.checksum);
110  return false;
111  }
112  return true;
113 }
114 
116 {
117  if (!sync_frame_start()) {
118  return;
119  }
120  struct frame irframe;
121 
122  if (!read_block(irframe)) {
123  return;
124  }
125 
126  int16_t corner1_pix_x = irframe.pixel_x - irframe.pixel_size_x/2;
127  int16_t corner1_pix_y = irframe.pixel_y - irframe.pixel_size_y/2;
128  int16_t corner2_pix_x = irframe.pixel_x + irframe.pixel_size_x/2;
129  int16_t corner2_pix_y = irframe.pixel_y + irframe.pixel_size_y/2;
130 
131  float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y;
132  pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y);
133  pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y);
134 
136  /* convert to angles */
138  _target_info.pos_x = 0.5f*(corner1_pos_x+corner2_pos_x);
139  _target_info.pos_y = 0.5f*(corner1_pos_y+corner2_pos_y);
140  _target_info.size_x = corner2_pos_x-corner1_pos_x;
141  _target_info.size_y = corner2_pos_y-corner1_pos_y;
142  sem->give();
143  }
144 
145 #if 0
146  // debugging
147  static uint32_t lastt;
148  if (_target_info.timestamp - lastt > 2000) {
149  lastt = _target_info.timestamp;
150  printf("pos_x:%.5f pos_y:%.5f size_x:%.6f size_y:%.5f\n",
153  }
154 #endif
155 }
156 
157 // retrieve latest sensor data - returns true if new data is available
159 {
160  bool new_data = false;
161  if (!dev || !sem) {
162  return false;
163  }
166  new_data = true;
167  }
170  sem->give();
171  }
172  // return true if new data found
173  return new_data;
174 }
int printf(const char *fmt,...)
Definition: stdio.c:113
#define IRLOCK_SYNC
#define IRLOCK_I2C_ADDRESS
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
bool update() override
AP_HAL::Util * util
Definition: HAL.h:115
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
uint32_t _last_read_ms
Definition: AP_IRLock_I2C.h:39
irlock_target_info _target_info
Definition: IRLock.h:71
AP_HAL::Semaphore * sem
Definition: AP_IRLock_I2C.h:38
#define f(i)
uint32_t millis()
Definition: system.cpp:157
void init(int8_t bus) override
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual bool give()=0
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y)
bool read_block(struct frame &irframe)
void read_frames(void)
uint32_t _last_update_ms
Definition: IRLock.h:60
struct IRLock::AP_IRLock_Flags _flags
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: AP_IRLock_I2C.h:19
bool sync_frame_start(void)