|
|
@ -42,18 +42,14 @@ float AC_PrecLand_Companion::distance_to_target() |
|
|
|
return _distance_to_target; |
|
|
|
return _distance_to_target; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void AC_PrecLand_Companion::handle_msg(const mavlink_message_t &msg) |
|
|
|
void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) |
|
|
|
{ |
|
|
|
{ |
|
|
|
// parse mavlink message
|
|
|
|
|
|
|
|
__mavlink_landing_target_t packet; |
|
|
|
|
|
|
|
mavlink_msg_landing_target_decode(&msg, &packet); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
_distance_to_target = packet.distance; |
|
|
|
_distance_to_target = packet.distance; |
|
|
|
|
|
|
|
|
|
|
|
// compute unit vector towards target
|
|
|
|
// compute unit vector towards target
|
|
|
|
_los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f); |
|
|
|
_los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f); |
|
|
|
_los_meas_body /= _los_meas_body.length(); |
|
|
|
_los_meas_body /= _los_meas_body.length(); |
|
|
|
|
|
|
|
|
|
|
|
_los_meas_time_ms = AP_HAL::millis(); |
|
|
|
_los_meas_time_ms = timestamp_ms; |
|
|
|
_have_los_meas = true; |
|
|
|
_have_los_meas = true; |
|
|
|
} |
|
|
|
} |
|
|
|