precland: support receiving LANDING_TARGET message

This commit is contained in:
Oleg Kalachev
2018-03-27 19:19:53 +03:00
committed by Kabir Mohammed
parent 5b030535c8
commit 8d6bff08bb
4 changed files with 41 additions and 8 deletions
+28
View File
@@ -132,6 +132,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_land_detector_pub(nullptr),
_time_offset_pub(nullptr),
_follow_target_pub(nullptr),
_landing_target_pose_pub(nullptr),
_transponder_report_pub(nullptr),
_collision_report_pub(nullptr),
_debug_key_value_pub(nullptr),
@@ -294,6 +295,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_follow_target(msg);
break;
case MAVLINK_MSG_ID_LANDING_TARGET:
handle_message_landing_target(msg);
break;
case MAVLINK_MSG_ID_ADSB_VEHICLE:
handle_message_adsb_vehicle(msg);
break;
@@ -2059,6 +2064,29 @@ void MavlinkReceiver::handle_message_follow_target(mavlink_message_t *msg)
}
}
void MavlinkReceiver::handle_message_landing_target(mavlink_message_t *msg)
{
mavlink_landing_target_t landing_target;
mavlink_msg_landing_target_decode(msg, &landing_target);
if (landing_target.position_valid && landing_target.frame == MAV_FRAME_LOCAL_NED) {
landing_target_pose_s landing_target_pose = {};
landing_target_pose.timestamp = sync_stamp(landing_target.time_usec);
landing_target_pose.abs_pos_valid = true;
landing_target_pose.x_abs = landing_target.x;
landing_target_pose.y_abs = landing_target.y;
landing_target_pose.z_abs = landing_target.z;
if (_landing_target_pose_pub == nullptr) {
_landing_target_pose_pub = orb_advertise(ORB_ID(landing_target_pose), &landing_target_pose);
} else {
orb_publish(ORB_ID(landing_target_pose), _landing_target_pose_pub, &landing_target_pose);
}
}
}
void MavlinkReceiver::handle_message_adsb_vehicle(mavlink_message_t *msg)
{
mavlink_adsb_vehicle_t adsb;
+3
View File
@@ -74,6 +74,7 @@
#include <uORB/topics/time_offset.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/follow_target.h>
#include <uORB/topics/landing_target_pose.h>
#include <uORB/topics/transponder_report.h>
#include <uORB/topics/gps_inject_data.h>
#include <uORB/topics/collision_report.h>
@@ -149,6 +150,7 @@ private:
void handle_message_hil_state_quaternion(mavlink_message_t *msg);
void handle_message_distance_sensor(mavlink_message_t *msg);
void handle_message_follow_target(mavlink_message_t *msg);
void handle_message_landing_target(mavlink_message_t *msg);
void handle_message_adsb_vehicle(mavlink_message_t *msg);
void handle_message_collision(mavlink_message_t *msg);
void handle_message_gps_rtcm_data(mavlink_message_t *msg);
@@ -242,6 +244,7 @@ private:
orb_advert_t _land_detector_pub;
orb_advert_t _time_offset_pub;
orb_advert_t _follow_target_pub;
orb_advert_t _landing_target_pose_pub;
orb_advert_t _transponder_report_pub;
orb_advert_t _collision_report_pub;
orb_advert_t _debug_key_value_pub;
+9 -8
View File
@@ -108,10 +108,9 @@ void
PrecLand::on_active()
{
// get new target measurement
bool updated = false;
orb_check(_target_pose_sub, &updated);
orb_check(_target_pose_sub, &_target_pose_updated);
if (updated) {
if (_target_pose_updated) {
orb_copy(ORB_ID(landing_target_pose), _target_pose_sub, &_target_pose);
_target_pose_valid = true;
}
@@ -466,7 +465,7 @@ bool PrecLand::check_state_conditions(PrecLandState state)
// if we're already in this state, only want to make it invalid if we reached the target but can't see it anymore
if (_state == PrecLandState::HorizontalApproach) {
if (fabsf(_target_pose.x_abs - vehicle_local_position->x) < _param_hacc_rad.get()
&& fabsf(_target_pose.y_rel - vehicle_local_position->y) < _param_hacc_rad.get()) {
&& fabsf(_target_pose.y_abs - vehicle_local_position->y) < _param_hacc_rad.get()) {
// we've reached the position where we last saw the target. If we don't see it now, we need to do something
return _target_pose_valid && _target_pose.abs_pos_valid;
@@ -478,7 +477,7 @@ bool PrecLand::check_state_conditions(PrecLandState state)
}
// If we're trying to switch to this state, the target needs to be visible
return _target_pose_valid && _target_pose.abs_pos_valid;
return _target_pose_updated && _target_pose.abs_pos_valid;
case PrecLandState::DescendAboveTarget:
@@ -494,12 +493,14 @@ bool PrecLand::check_state_conditions(PrecLandState state)
} else {
// if not already in this state, need to be above target to enter it
return _target_pose_valid && _target_pose.abs_pos_valid
&& fabsf(_target_pose.x_rel) < _param_hacc_rad.get() && fabsf(_target_pose.y_rel) < _param_hacc_rad.get();
return _target_pose_updated && _target_pose.abs_pos_valid
&& fabsf(_target_pose.x_abs - vehicle_local_position->x) < _param_hacc_rad.get()
&& fabsf(_target_pose.y_abs - vehicle_local_position->y) < _param_hacc_rad.get();
}
case PrecLandState::FinalApproach:
return _target_pose_valid && _target_pose.rel_pos_valid && _target_pose.z_rel < _param_final_approach_alt.get();
return _target_pose_valid && _target_pose.abs_pos_valid
&& (_target_pose.z_abs - vehicle_local_position->z) < _param_final_approach_alt.get();
case PrecLandState::Search:
return true;
+1
View File
@@ -102,6 +102,7 @@ private:
int _target_pose_sub{-1};
bool _target_pose_valid{false}; /**< whether we have received a landing target position message */
bool _target_pose_updated{false}; /**< wether the landing target position message is updated */
struct map_projection_reference_s _map_ref {}; /**< reference for local/global projections */