Copter: do not log CURR.Throttle because it's already logged elsewhere
This commit is contained in:
parent
098e531d53
commit
a96abde4bf
@ -216,7 +216,7 @@ void Copter::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
|
|||||||
// Write a Current data packet
|
// Write a Current data packet
|
||||||
void Copter::Log_Write_Current()
|
void Copter::Log_Write_Current()
|
||||||
{
|
{
|
||||||
DataFlash.Log_Write_Current(battery, (int16_t)(motors.get_throttle()));
|
DataFlash.Log_Write_Current(battery);
|
||||||
|
|
||||||
// also write power status
|
// also write power status
|
||||||
DataFlash.Log_Write_Power();
|
DataFlash.Log_Write_Power();
|
||||||
|
Loading…
Reference in New Issue
Block a user