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