mirror of https://github.com/ArduPilot/ardupilot
Copter: use handle_landing_target() for precland
allows for jitter correction
This commit is contained in:
parent
8444a3310d
commit
5a869174e5
|
@ -568,6 +568,16 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)
|
||||||
GCS_MAVLINK::handle_command_ack(msg);
|
GCS_MAVLINK::handle_command_ack(msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
handle a LANDING_TARGET command. The timestamp has been jitter corrected
|
||||||
|
*/
|
||||||
|
void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
|
||||||
|
{
|
||||||
|
#if PRECISION_LANDING == ENABLED
|
||||||
|
copter.precland.handle_msg(packet, timestamp_ms);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
if (is_equal(packet.param6,1.0f)) {
|
if (is_equal(packet.param6,1.0f)) {
|
||||||
|
@ -1281,12 +1291,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if PRECISION_LANDING == ENABLED
|
|
||||||
case MAVLINK_MSG_ID_LANDING_TARGET:
|
|
||||||
copter.precland.handle_msg(msg);
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_TERRAIN_DATA:
|
case MAVLINK_MSG_ID_TERRAIN_DATA:
|
||||||
case MAVLINK_MSG_ID_TERRAIN_CHECK:
|
case MAVLINK_MSG_ID_TERRAIN_CHECK:
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
|
|
|
@ -35,6 +35,8 @@ protected:
|
||||||
|
|
||||||
void handle_mount_message(const mavlink_message_t &msg) override;
|
void handle_mount_message(const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
|
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||||
void send_nav_controller_output() const override;
|
void send_nav_controller_output() const override;
|
||||||
|
|
Loading…
Reference in New Issue