Copter: implement get_wp() for follow

this allows the GCS to plot the position target
This commit is contained in:
Andrew Tridgell 2018-12-30 16:55:05 +11:00 committed by Randy Mackay
parent e6bc44f471
commit cc4db3e458
2 changed files with 13 additions and 0 deletions

View File

@ -1142,6 +1142,7 @@ protected:
const char *name4() const override { return "FOLL"; } const char *name4() const override { return "FOLL"; }
uint32_t wp_distance() const override; uint32_t wp_distance() const override;
int32_t wp_bearing() const override; int32_t wp_bearing() const override;
bool get_wp(Location_Class &loc) override;
uint32_t last_log_ms; // system time of last time desired velocity was logging uint32_t last_log_ms; // system time of last time desired velocity was logging
}; };

View File

@ -160,4 +160,16 @@ int32_t Copter::ModeFollow::wp_bearing() const
return g2.follow.get_bearing_to_target() * 100; return g2.follow.get_bearing_to_target() * 100;
} }
/*
get target position for mavlink reporting
*/
bool Copter::ModeFollow::get_wp(Location_Class &loc)
{
float dist = g2.follow.get_distance_to_target();
float bearing = g2.follow.get_bearing_to_target();
loc = copter.current_loc;
location_update(loc, bearing, dist);
return true;
}
#endif // MODE_FOLLOW_ENABLED == ENABLED #endif // MODE_FOLLOW_ENABLED == ENABLED