2015-08-28 05:11:52 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AC_PrecLand_Companion.h"
|
2015-02-16 00:37:13 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// Constructor
|
|
|
|
AC_PrecLand_Companion::AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state)
|
2015-11-12 01:43:38 -04:00
|
|
|
: AC_PrecLand_Backend(frontend, state),
|
|
|
|
_timestamp_us(0),
|
2016-07-23 02:49:21 -03:00
|
|
|
_distance_to_target(0.0f),
|
2016-08-08 01:11:20 -03:00
|
|
|
_have_los_meas(false),
|
|
|
|
_los_meas_time_ms(0)
|
2015-02-16 00:37:13 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// perform any required initialisation of backend
|
2015-02-16 00:37:13 -04:00
|
|
|
void AC_PrecLand_Companion::init()
|
|
|
|
{
|
|
|
|
// set healthy
|
|
|
|
_state.healthy = true;
|
2016-07-05 16:37:17 -03:00
|
|
|
_have_los_meas = false;
|
2015-02-16 00:37:13 -04:00
|
|
|
}
|
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// retrieve updates from sensor
|
|
|
|
void AC_PrecLand_Companion::update()
|
2015-02-16 00:37:13 -04:00
|
|
|
{
|
2016-07-05 16:37:17 -03:00
|
|
|
_have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000;
|
2015-02-16 00:37:13 -04:00
|
|
|
}
|
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// provides a unit vector towards the target in body frame
|
|
|
|
// returns same as have_los_meas()
|
|
|
|
bool AC_PrecLand_Companion::get_los_body(Vector3f& ret) {
|
|
|
|
if (have_los_meas()) {
|
|
|
|
ret = _los_meas_body;
|
2015-09-11 08:00:18 -03:00
|
|
|
return true;
|
|
|
|
}
|
2015-02-16 00:37:13 -04:00
|
|
|
return false;
|
|
|
|
}
|
2015-09-11 08:00:18 -03:00
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// returns system time in milliseconds of last los measurement
|
|
|
|
uint32_t AC_PrecLand_Companion::los_meas_time_ms() {
|
|
|
|
return _los_meas_time_ms;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return true if there is a valid los measurement available
|
|
|
|
bool AC_PrecLand_Companion::have_los_meas()
|
|
|
|
{
|
|
|
|
return _have_los_meas;
|
|
|
|
}
|
|
|
|
|
2015-09-11 08:00:18 -03:00
|
|
|
void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg)
|
|
|
|
{
|
|
|
|
// parse mavlink message
|
|
|
|
__mavlink_landing_target_t packet;
|
|
|
|
mavlink_msg_landing_target_decode(msg, &packet);
|
|
|
|
|
|
|
|
_timestamp_us = packet.time_usec;
|
|
|
|
_distance_to_target = packet.distance;
|
2016-07-05 16:37:17 -03:00
|
|
|
|
|
|
|
// compute unit vector towards target
|
|
|
|
_los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f);
|
|
|
|
_los_meas_body /= _los_meas_body.length();
|
|
|
|
|
|
|
|
_los_meas_time_ms = AP_HAL::millis();
|
|
|
|
_have_los_meas = true;
|
2015-09-11 08:00:18 -03:00
|
|
|
}
|