mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: params always use set method
This commit is contained in:
parent
3878e64f97
commit
ea03ea320c
|
@ -1573,7 +1573,7 @@ AP_InertialSensor::_init_gyro()
|
|||
_gyro_cal_ok[k] = true;
|
||||
_gyro_offset[k] = new_gyro_offset[k];
|
||||
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
||||
caltemp_gyro[k] = 0.5 * (get_temperature(k) + start_temperature[k]);
|
||||
caltemp_gyro[k].set(0.5 * (get_temperature(k) + start_temperature[k]));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -56,7 +56,7 @@ void AP_InertialSensor::BatchSampler::init()
|
|||
return;
|
||||
}
|
||||
|
||||
_required_count -= _required_count % 32; // round down to nearest multiple of 32
|
||||
_required_count.set(_required_count - (_required_count % 32)); // round down to nearest multiple of 32
|
||||
|
||||
const uint32_t total_allocation = 3*_required_count*sizeof(uint16_t);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "INS: alloc %u bytes for ISB (free=%u)", (unsigned int)total_allocation, (unsigned int)hal.util->available_memory());
|
||||
|
|
Loading…
Reference in New Issue