mirror of https://github.com/ArduPilot/ardupilot
Copter: follow return wp_distance and wp_bearing
This commit is contained in:
parent
4b6db7c0dd
commit
7a6e212da9
|
@ -1252,6 +1252,8 @@ protected:
|
|||
|
||||
const char *name() const override { return "FOLLOW"; }
|
||||
const char *name4() const override { return "FOLL"; }
|
||||
uint32_t wp_distance() const override;
|
||||
int32_t wp_bearing() const override;
|
||||
|
||||
uint32_t last_log_ms; // system time of last time desired velocity was logging
|
||||
};
|
||||
|
|
|
@ -150,4 +150,14 @@ void Copter::ModeFollow::run()
|
|||
Copter::ModeGuided::run();
|
||||
}
|
||||
|
||||
uint32_t Copter::ModeFollow::wp_distance() const
|
||||
{
|
||||
return g2.follow.get_distance_to_target() * 100;
|
||||
}
|
||||
|
||||
int32_t Copter::ModeFollow::wp_bearing() const
|
||||
{
|
||||
return g2.follow.get_bearing_to_target() * 100;
|
||||
}
|
||||
|
||||
#endif // MODE_FOLLOW_ENABLED == ENABLED
|
||||
|
|
Loading…
Reference in New Issue