AP_Logger: remove rally argument from Write_Rally - use singleton

This commit is contained in:
Peter Barker 2019-01-31 11:04:51 +11:00 committed by Randy Mackay
parent 3766ee1b60
commit 5ecb730766
2 changed files with 9 additions and 5 deletions

View File

@ -138,7 +138,7 @@ public:
const AP_Motors &motors,
const AC_AttitudeControl &attitude_control,
const AC_PosControl &pos_control);
void Write_Rally(const AP_Rally &rally);
void Write_Rally();
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
void Write_AOA_SSA(AP_AHRS &ahrs);
void Write_Beacon(AP_Beacon &beacon);

View File

@ -1608,15 +1608,19 @@ void AP_Logger::Write_Rate(const AP_AHRS_View *ahrs,
}
// Write rally points
void AP_Logger::Write_Rally(const AP_Rally &rally)
void AP_Logger::Write_Rally()
{
const AP_Rally *rally = AP::rally();
if (rally == nullptr) {
return;
}
RallyLocation rally_point;
for (uint8_t i=0; i<rally.get_rally_total(); i++) {
if (rally.get_rally_point_with_index(i, rally_point)) {
for (uint8_t i=0; i<rally->get_rally_total(); i++) {
if (rally->get_rally_point_with_index(i, rally_point)) {
struct log_Rally pkt_rally = {
LOG_PACKET_HEADER_INIT(LOG_RALLY_MSG),
time_us : AP_HAL::micros64(),
total : rally.get_rally_total(),
total : rally->get_rally_total(),
sequence : i,
latitude : rally_point.lat,
longitude : rally_point.lng,