DataFlash: use rangefinder backend accessors

This commit is contained in:
Peter Barker 2017-08-08 16:15:07 +10:00 committed by Francisco Ferreira
parent 63440800fc
commit f1d350bbb1

View File

@ -10,6 +10,7 @@
#include <AP_Motors/AP_Motors.h>
#include <AC_AttitudeControl/AC_AttitudeControl.h>
#include <AC_AttitudeControl/AC_PosControl.h>
#include <AP_RangeFinder/RangeFinder_Backend.h>
#include "DataFlash.h"
#include "DataFlash_File.h"
@ -290,13 +291,16 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, uint64_t time_
// Write an RFND (rangefinder) packet
void DataFlash_Class::Log_Write_RFND(const RangeFinder &rangefinder)
{
AP_RangeFinder_Backend *s0 = rangefinder.get_backend(0);
AP_RangeFinder_Backend *s1 = rangefinder.get_backend(1);
struct log_RFND pkt = {
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_RFND_MSG)),
time_us : AP_HAL::micros64(),
dist1 : rangefinder.distance_cm(0),
orient1 : rangefinder.get_orientation(0),
dist2 : rangefinder.distance_cm(1),
orient2 : rangefinder.get_orientation(1)
dist1 : s0 ? s0->distance_cm() : (uint16_t)0,
orient1 : s0 ? s0->orientation() : ROTATION_NONE,
dist2 : s1 ? s1->distance_cm() : (uint16_t)0,
orient2 : s1 ? s1->orientation() : ROTATION_NONE,
};
WriteBlock(&pkt, sizeof(pkt));
}