2016-09-14 20:31:16 -03:00
|
|
|
/*
|
|
|
|
* AP_IRLock_SITL.h
|
|
|
|
*
|
|
|
|
* Created on: June 09, 2016
|
|
|
|
* Author: Ian Chen
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/utility/Socket.h>
|
2016-11-17 14:05:04 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2016-09-14 20:31:16 -03:00
|
|
|
#include "IRLock.h"
|
|
|
|
|
|
|
|
class AP_IRLock_SITL : public IRLock
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_IRLock_SITL();
|
|
|
|
|
|
|
|
// init - initialize sensor library
|
2017-04-13 17:40:41 -03:00
|
|
|
void init(int8_t bus) override;
|
2016-09-14 20:31:16 -03:00
|
|
|
|
|
|
|
// retrieve latest sensor data - returns true if new data is available
|
2017-04-13 17:40:41 -03:00
|
|
|
bool update() override;
|
2016-09-14 20:31:16 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
/*
|
|
|
|
reply packet sent from simulator to ArduPilot
|
|
|
|
*/
|
|
|
|
struct irlock_packet {
|
2017-01-19 10:17:08 -04:00
|
|
|
uint64_t timestamp; // in miliseconds
|
2016-11-26 01:22:18 -04:00
|
|
|
uint16_t num_targets;
|
|
|
|
float pos_x;
|
|
|
|
float pos_y;
|
|
|
|
float size_x;
|
|
|
|
float size_y;
|
|
|
|
};
|
|
|
|
|
|
|
|
uint32_t _last_timestamp;
|
2016-09-14 20:31:16 -03:00
|
|
|
SocketAPM sock;
|
|
|
|
};
|
2016-11-17 14:05:04 -04:00
|
|
|
#endif // CONFIG_HAL_BOARD
|