2015-02-16 00:37:13 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
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),
|
|
|
|
_frame(MAV_FRAME_BODY_NED),
|
|
|
|
_distance_to_target(0.0f),
|
|
|
|
_timestamp_us(0),
|
|
|
|
_new_estimate(false)
|
2015-02-16 00:37:13 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
// init - perform initialisation of this backend
|
|
|
|
void AC_PrecLand_Companion::init()
|
|
|
|
{
|
|
|
|
// set healthy
|
|
|
|
_state.healthy = true;
|
2015-09-11 08:00:18 -03:00
|
|
|
_new_estimate = false;
|
2015-02-16 00:37:13 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// update - give chance to driver to get updates from sensor
|
|
|
|
// returns true if new data available
|
|
|
|
bool AC_PrecLand_Companion::update()
|
|
|
|
{
|
2015-09-11 08:00:18 -03:00
|
|
|
// Mavlink commands are received asynchronous so all new data is processed by handle_msg()
|
|
|
|
return _new_estimate;
|
2015-02-16 00:37:13 -04:00
|
|
|
}
|
|
|
|
|
2015-10-23 12:18:35 -03:00
|
|
|
MAV_FRAME AC_PrecLand_Companion::get_frame_of_reference()
|
|
|
|
{
|
|
|
|
return _frame;
|
|
|
|
}
|
|
|
|
|
2015-10-23 14:04:40 -03:00
|
|
|
// get_angle_to_target - returns angles (in radians) to target
|
2015-02-16 00:37:13 -04:00
|
|
|
// returns true if angles are available, false if not (i.e. no target)
|
2015-10-23 14:04:40 -03:00
|
|
|
// x_angle_rad : roll direction, positive = target is to right (looking down)
|
|
|
|
// y_angle_rad : pitch direction, postiive = target is forward (looking down)
|
2015-09-11 08:00:18 -03:00
|
|
|
bool AC_PrecLand_Companion::get_angle_to_target(float &x_angle_rad, float &y_angle_rad)
|
2015-02-16 00:37:13 -04:00
|
|
|
{
|
2015-09-11 08:00:18 -03:00
|
|
|
if (_new_estimate){
|
2015-10-23 12:15:40 -03:00
|
|
|
x_angle_rad = _angle_to_target.x;
|
|
|
|
y_angle_rad = _angle_to_target.y;
|
2015-09-11 08:00:18 -03:00
|
|
|
|
|
|
|
// reset and wait for new data
|
|
|
|
_new_estimate = false;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2015-02-16 00:37:13 -04:00
|
|
|
return false;
|
|
|
|
}
|
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;
|
2015-10-23 12:18:35 -03:00
|
|
|
_frame = (MAV_FRAME) packet.frame;
|
2015-10-23 12:15:40 -03:00
|
|
|
_angle_to_target.x = packet.angle_x;
|
|
|
|
_angle_to_target.y = packet.angle_y;
|
2015-09-11 08:00:18 -03:00
|
|
|
_distance_to_target = packet.distance;
|
|
|
|
_state.healthy = true;
|
|
|
|
_new_estimate = true;
|
|
|
|
}
|