mirror of https://github.com/ArduPilot/ardupilot
Rover: handle landing target mavlink message
This commit is contained in:
parent
bc3ff20871
commit
7b573fa2c4
|
@ -1072,6 +1072,15 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
|
||||||
handle_radio_status(msg, rover.should_log(MASK_LOG_PM));
|
handle_radio_status(msg, rover.should_log(MASK_LOG_PM));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
handle a LANDING_TARGET command. The timestamp has been jitter corrected
|
||||||
|
*/
|
||||||
|
void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
|
||||||
|
{
|
||||||
|
#if PRECISION_LANDING == ENABLED
|
||||||
|
rover.precland.handle_msg(packet, timestamp_ms);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
uint64_t GCS_MAVLINK_Rover::capabilities() const
|
uint64_t GCS_MAVLINK_Rover::capabilities() const
|
||||||
{
|
{
|
||||||
|
|
|
@ -42,6 +42,7 @@ private:
|
||||||
void handle_set_position_target_local_ned(const mavlink_message_t &msg);
|
void handle_set_position_target_local_ned(const mavlink_message_t &msg);
|
||||||
void handle_set_position_target_global_int(const mavlink_message_t &msg);
|
void handle_set_position_target_global_int(const mavlink_message_t &msg);
|
||||||
void handle_radio(const mavlink_message_t &msg);
|
void handle_radio(const mavlink_message_t &msg);
|
||||||
|
void handle_landing_target(const mavlink_landing_target_t &msg, uint32_t timestamp_ms) override;
|
||||||
|
|
||||||
void send_servo_out();
|
void send_servo_out();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue