mirror of https://github.com/ArduPilot/ardupilot
Copter: implement set_target_location method
This commit is contained in:
parent
6f5d733ba9
commit
a9630d67d1
|
@ -271,6 +271,17 @@ void Copter::fast_loop()
|
|||
}
|
||||
}
|
||||
|
||||
// set target location (for use by scripting)
|
||||
bool Copter::set_target_location(const Location& target_loc)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
if (!flightmode->in_guided_mode()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return mode_guided.set_destination(target_loc);
|
||||
}
|
||||
|
||||
// rc_loops - reads user input from transmitter/receiver
|
||||
// called at 100hz
|
||||
void Copter::rc_loop()
|
||||
|
|
|
@ -636,6 +636,7 @@ private:
|
|||
uint8_t &task_count,
|
||||
uint32_t &log_bit) override;
|
||||
void fast_loop() override;
|
||||
bool set_target_location(const Location& target_loc) override;
|
||||
void rc_loop();
|
||||
void throttle_loop();
|
||||
void update_batt_compass(void);
|
||||
|
|
Loading…
Reference in New Issue