mirror of https://github.com/ArduPilot/ardupilot
DataFlash: pass ahrs, batt, targets by reference
This commit is contained in:
parent
f23959b5fa
commit
09e3dcd821
|
@ -82,8 +82,8 @@ public:
|
|||
void Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, const Location ¤t_loc);
|
||||
void Log_Write_ESC(void);
|
||||
void Log_Write_Airspeed(AP_Airspeed &airspeed);
|
||||
void Log_Write_Attitude(AP_AHRS &ahrs, Vector3f targets);
|
||||
void Log_Write_Current(AP_BattMonitor battery, int16_t throttle);
|
||||
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
||||
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
|
||||
void Log_Write_Compass(const Compass &compass);
|
||||
void Log_Write_Mode(uint8_t mode);
|
||||
|
||||
|
|
|
@ -1108,7 +1108,7 @@ void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, c
|
|||
}
|
||||
|
||||
// Write an attitude packet
|
||||
void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, Vector3f targets)
|
||||
void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
|
||||
{
|
||||
struct log_Attitude pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
|
||||
|
@ -1126,7 +1126,7 @@ void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, Vector3f targets)
|
|||
}
|
||||
|
||||
// Write an Current data packet
|
||||
void DataFlash_Class::Log_Write_Current(AP_BattMonitor battery, int16_t throttle)
|
||||
void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle)
|
||||
{
|
||||
float voltage2 = battery.voltage2();
|
||||
struct log_Current pkt = {
|
||||
|
|
Loading…
Reference in New Issue