mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Copter: Log.pde: replace unused copy with ref (saves again some bytes)
This commit is contained in:
parent
e2c3ea0f56
commit
d6d5f0bbe4
@ -339,7 +339,7 @@ struct PACKED log_Nav_Tuning {
|
|||||||
// Write an Nav Tuning packet
|
// Write an Nav Tuning packet
|
||||||
static void Log_Write_Nav_Tuning()
|
static void Log_Write_Nav_Tuning()
|
||||||
{
|
{
|
||||||
Vector3f velocity = inertial_nav.get_velocity();
|
const Vector3f &velocity = inertial_nav.get_velocity();
|
||||||
|
|
||||||
struct log_Nav_Tuning pkt = {
|
struct log_Nav_Tuning pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
|
||||||
@ -525,7 +525,7 @@ struct PACKED log_INAV {
|
|||||||
// Write an INAV packet
|
// Write an INAV packet
|
||||||
static void Log_Write_INAV()
|
static void Log_Write_INAV()
|
||||||
{
|
{
|
||||||
Vector3f accel_corr = inertial_nav.accel_correction_ef;
|
const Vector3f &accel_corr = inertial_nav.accel_correction_ef;
|
||||||
|
|
||||||
struct log_INAV pkt = {
|
struct log_INAV pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_INAV_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_INAV_MSG),
|
||||||
|
Loading…
Reference in New Issue
Block a user