mirror of https://github.com/ArduPilot/ardupilot
Rover: implement set_target_location method
This commit is contained in:
parent
a9630d67d1
commit
93f87b215b
|
@ -139,6 +139,17 @@ Rover::Rover(void) :
|
|||
{
|
||||
}
|
||||
|
||||
// set target location (for use by scripting)
|
||||
bool Rover::set_target_location(const Location& target_loc)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
if (!control_mode->in_guided_mode()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return control_mode->set_desired_location(target_loc);
|
||||
}
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
/*
|
||||
update AP_Stats
|
||||
|
|
|
@ -276,7 +276,8 @@ private:
|
|||
|
||||
private:
|
||||
|
||||
// APMrover2.cpp
|
||||
// Rover.cpp
|
||||
bool set_target_location(const Location& target_loc) override;
|
||||
void stats_update();
|
||||
void ahrs_update();
|
||||
void gcs_failsafe_check(void);
|
||||
|
|
Loading…
Reference in New Issue