GCS_MAVLink: added handle_command_landing_target()

used to allow vehicle handling of time corrected LANDING_TARGET msgs
This commit is contained in:
Andrew Tridgell 2019-05-31 20:58:27 +10:00 committed by Peter Barker
parent cc4fe29d8f
commit 8444a3310d
2 changed files with 18 additions and 0 deletions

View File

@ -504,6 +504,8 @@ protected:
MAV_RESULT handle_fixed_mag_cal_yaw(const mavlink_command_long_t &packet);
// default empty handling of LANDING_TARGET
virtual void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { }
// vehicle-overridable message send function
virtual bool try_send_message(enum ap_message id);
virtual void send_global_position_int();
@ -802,6 +804,7 @@ private:
const uint8_t reset_counter,
const uint16_t payload_size);
void handle_vision_speed_estimate(const mavlink_message_t &msg);
void handle_landing_target(const mavlink_message_t &msg);
void lock_channel(const mavlink_channel_t chan, bool lock);

View File

@ -3561,6 +3561,10 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG:
handle_osd_param_config(msg);
break;
case MAVLINK_MSG_ID_LANDING_TARGET:
handle_landing_target(msg);
break;
}
}
@ -4350,6 +4354,17 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const Location &roi_loc)
#endif
}
void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg)
{
mavlink_landing_target_t m;
mavlink_msg_landing_target_decode(&msg, &m);
// correct offboard timestamp
const uint32_t corrected_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, LANDING_TARGET));
handle_landing_target(m, corrected_ms);
}
MAV_RESULT GCS_MAVLINK::handle_command_int_do_set_home(const mavlink_command_int_t &packet)
{
if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) {