APM:Libraries
AP_IRLock_SITL.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_SITL.cpp
18  *
19  * Created on: June 09, 2016
20  * Author: Ian Chen
21  */
22 #include <AP_HAL/AP_HAL.h>
23 
24 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
25 #include "AP_IRLock_SITL.h"
26 #include <SITL/SITL.h>
27 #include <fcntl.h>
28 #include <unistd.h>
29 
30 #include <iostream>
31 
32 extern const AP_HAL::HAL& hal;
33 
35  _last_timestamp(0),
36  sock(true)
37 {}
38 
39 void AP_IRLock_SITL::init(int8_t bus)
40 {
42  // try to bind to a specific port so that if we restart ArduPilot
43  // Gazebo keeps sending us packets. Not strictly necessary but
44  // useful for debugging
45  sock.bind("127.0.0.1", sitl->irlock_port);
46 
47  sock.reuseaddress();
48  sock.set_blocking(false);
49 
50  hal.console->printf("AP_IRLock_SITL::init()\n");
51 
52  _flags.healthy = true;
53 }
54 
55 // retrieve latest sensor data - returns true if new data is available
57 {
58  // return immediately if not healthy
59  if (!_flags.healthy) {
60  return false;
61  }
62 
63  // receive packet from Gazebo IRLock plugin
64  irlock_packet pkt;
65  const int wait_ms = 0;
66  ssize_t s = sock.recv(&pkt, sizeof(irlock_packet), wait_ms);
67 
68  bool new_data = false;
69 
70  if (s == sizeof(irlock_packet) && pkt.timestamp > _last_timestamp) {
71  // fprintf(stderr, " posx %f posy %f sizex %f sizey %f\n", pkt.pos_x, pkt.pos_y, pkt.size_x, pkt.size_y);
73  _target_info.pos_x = pkt.pos_x;
74  _target_info.pos_y = pkt.pos_y;
79  new_data = true;
80  }
81 
82  // return true if new data found
83  return new_data;
84 }
85 
86 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
uint16_t irlock_port
Definition: SITL.h:192
AP_HAL::UARTDriver * console
Definition: HAL.h:110
SocketAPM sock
irlock_target_info _target_info
Definition: IRLock.h:71
SITL::SITL * sitl()
Definition: SITL.cpp:229
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 void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool update() override
void init(int8_t bus) override
uint32_t _last_update_ms
Definition: IRLock.h:60
struct IRLock::AP_IRLock_Flags _flags
uint32_t _last_timestamp