CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp
Views: 1798
1
#include "AC_PrecLand_config.h"
2
3
#if AC_PRECLAND_COMPANION_ENABLED
4
5
#include "AC_PrecLand_Companion.h"
6
#include <AP_HAL/AP_HAL.h>
7
#include <GCS_MAVLink/GCS.h>
8
9
// perform any required initialisation of backend
10
void AC_PrecLand_Companion::init()
11
{
12
// set healthy
13
_state.healthy = true;
14
}
15
16
// retrieve updates from sensor
17
void AC_PrecLand_Companion::update()
18
{
19
_have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000;
20
}
21
22
void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
23
{
24
_distance_to_target = packet.distance;
25
26
if (packet.position_valid == 1) {
27
if (packet.frame == MAV_FRAME_BODY_FRD) {
28
if (_distance_to_target > 0) {
29
_los_meas_body = Vector3f(packet.x, packet.y, packet.z);
30
_los_meas_body /= _distance_to_target;
31
} else {
32
// distance to target must be positive
33
return;
34
}
35
} else {
36
//we do not support this frame
37
if (!_wrong_frame_msg_sent) {
38
_wrong_frame_msg_sent = true;
39
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Plnd: Frame not supported ");
40
}
41
return;
42
}
43
} else {
44
// compute unit vector towards target
45
_los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f);
46
_los_meas_body /= _los_meas_body.length();
47
}
48
49
_los_meas_time_ms = timestamp_ms;
50
_have_los_meas = true;
51
}
52
53
#endif // AC_PRECLAND_COMPANION_ENABLED
54
55