Plane: use battery.voltage2 method for logging
This commit is contained in:
parent
5cdb8a4c2a
commit
7d18744094
@ -431,8 +431,7 @@ struct PACKED log_Arm_Disarm {
|
|||||||
|
|
||||||
static void Log_Write_Current()
|
static void Log_Write_Current()
|
||||||
{
|
{
|
||||||
float voltage2 = 0.0;
|
float voltage2 = battery.voltage2();
|
||||||
battery.voltage2(voltage2);
|
|
||||||
struct log_Current pkt = {
|
struct log_Current pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
||||||
time_ms : hal.scheduler->millis(),
|
time_ms : hal.scheduler->millis(),
|
||||||
|
Loading…
Reference in New Issue
Block a user