mirror of https://github.com/ArduPilot/ardupilot
Tracker: add support for mavlink set-home-position
This commit is contained in:
parent
9f6027b332
commit
fe6ca9afa3
|
@ -369,6 +369,13 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool GCS_MAVLINK_Tracker::set_home_to_current_location(bool lock) {
|
||||||
|
return tracker.set_home(AP::gps().location());
|
||||||
|
}
|
||||||
|
bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool lock) {
|
||||||
|
return tracker.set_home(loc);
|
||||||
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
switch (msg->msgid) {
|
||||||
|
|
|
@ -28,8 +28,8 @@ protected:
|
||||||
return 0; // what if we have been picked up and carried somewhere?
|
return 0; // what if we have been picked up and carried somewhere?
|
||||||
}
|
}
|
||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED { return false; }
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED { return false; }
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||||
uint64_t capabilities() const override;
|
uint64_t capabilities() const override;
|
||||||
|
|
||||||
void send_nav_controller_output() const override;
|
void send_nav_controller_output() const override;
|
||||||
|
|
Loading…
Reference in New Issue