APM:Libraries
libraries
AC_PrecLand
AC_PrecLand_IRLock.h
Go to the documentation of this file.
1
#pragma once
2
3
#include <
AP_Common/AP_Common.h
>
4
#include <
AP_Math/AP_Math.h
>
5
#include <
AC_PrecLand/AC_PrecLand_Backend.h
>
6
#include <
AP_IRLock/AP_IRLock.h
>
7
8
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
9
#include <
AP_IRLock/AP_IRLock_SITL.h
>
10
#endif
11
12
/*
13
* AC_PrecLand_IRLock - implements precision landing using target vectors provided
14
* by a companion computer (i.e. Odroid) communicating via MAVLink
15
*/
16
17
class
AC_PrecLand_IRLock
:
public
AC_PrecLand_Backend
18
{
19
public
:
20
21
// Constructor
22
AC_PrecLand_IRLock
(
const
AC_PrecLand
& frontend,
AC_PrecLand::precland_state
&
state
);
23
24
// perform any required initialisation of backend
25
void
init
()
override
;
26
27
// retrieve updates from sensor
28
void
update
()
override
;
29
30
// provides a unit vector towards the target in body frame
31
// returns same as have_los_meas()
32
bool
get_los_body
(
Vector3f
& ret)
override
;
33
34
// returns system time in milliseconds of last los measurement
35
uint32_t
los_meas_time_ms
()
override
;
36
37
// return true if there is a valid los measurement available
38
bool
have_los_meas
()
override
;
39
40
private
:
41
AP_IRLock_I2C
irlock
;
42
43
Vector3f
_los_meas_body
;
// unit vector in body frame pointing towards target
44
bool
_have_los_meas
;
// true if there is a valid measurement from the camera
45
uint32_t
_los_meas_time_ms
;
// system time in milliseconds when los was measured
46
};
AC_PrecLand
Definition:
AC_PrecLand.h:18
AC_PrecLand_IRLock::AC_PrecLand_IRLock
AC_PrecLand_IRLock(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
Definition:
AC_PrecLand_IRLock.cpp:7
AC_PrecLand_IRLock::irlock
AP_IRLock_I2C irlock
Definition:
AC_PrecLand_IRLock.h:41
AC_PrecLand_IRLock::get_los_body
bool get_los_body(Vector3f &ret) override
Definition:
AC_PrecLand_IRLock.cpp:40
AC_PrecLand_IRLock::los_meas_time_ms
uint32_t los_meas_time_ms() override
Definition:
AC_PrecLand_IRLock.cpp:49
state
static int state
Definition:
Util.cpp:20
AC_PrecLand_IRLock::init
void init() override
Definition:
AC_PrecLand_IRLock.cpp:16
AP_Math.h
AP_Common.h
Common definitions and utility routines for the ArduPilot libraries.
AP_IRLock.h
AC_PrecLand_IRLock
Definition:
AC_PrecLand_IRLock.h:17
AC_PrecLand_IRLock::_los_meas_body
Vector3f _los_meas_body
Definition:
AC_PrecLand_IRLock.h:43
AC_PrecLand_Backend
Definition:
AC_PrecLand_Backend.h:8
AC_PrecLand_IRLock::_los_meas_time_ms
uint32_t _los_meas_time_ms
Definition:
AC_PrecLand_IRLock.h:45
AC_PrecLand_IRLock::_have_los_meas
bool _have_los_meas
Definition:
AC_PrecLand_IRLock.h:44
AC_PrecLand_Backend.h
AC_PrecLand::precland_state
Definition:
AC_PrecLand.h:145
Vector3< float >
AC_PrecLand_IRLock::update
void update() override
Definition:
AC_PrecLand_IRLock.cpp:22
AP_IRLock_SITL.h
AP_IRLock_I2C
Definition:
AP_IRLock_I2C.h:9
AC_PrecLand_IRLock::have_los_meas
bool have_los_meas() override
Definition:
AC_PrecLand_IRLock.cpp:54
Generated on Sun Jun 17 2018 14:18:47 for APM:Libraries by
1.8.13