|
|
@ -52,6 +52,7 @@ |
|
|
|
#include <lib/matrix/matrix/math.hpp> |
|
|
|
#include <lib/matrix/matrix/math.hpp> |
|
|
|
#include <px4_time.h> |
|
|
|
#include <px4_time.h> |
|
|
|
#include <systemlib/mavlink_log.h> |
|
|
|
#include <systemlib/mavlink_log.h> |
|
|
|
|
|
|
|
#include <math.h> |
|
|
|
|
|
|
|
|
|
|
|
#include <uORB/topics/actuator_armed.h> |
|
|
|
#include <uORB/topics/actuator_armed.h> |
|
|
|
#include <uORB/topics/actuator_controls.h> |
|
|
|
#include <uORB/topics/actuator_controls.h> |
|
|
@ -704,7 +705,10 @@ protected: |
|
|
|
bat_msg.energy_consumed = -1; |
|
|
|
bat_msg.energy_consumed = -1; |
|
|
|
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1; |
|
|
|
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1; |
|
|
|
bat_msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.0f) : -1; |
|
|
|
bat_msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.0f) : -1; |
|
|
|
bat_msg.temperature = (battery_status.connected) ? (int16_t)battery_status.temperature : INT16_MAX; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
bool temperature_valid = battery_status.connected && PX4_ISFINITE(battery_status.temperature); |
|
|
|
|
|
|
|
bat_msg.temperature = temperature_valid ? (int16_t)(battery_status.temperature * 100.0f) : INT16_MAX; |
|
|
|
//bat_msg.average_current_battery = (battery_status.connected) ? battery_status.average_current_a * 100.0f : -1;
|
|
|
|
//bat_msg.average_current_battery = (battery_status.connected) ? battery_status.average_current_a * 100.0f : -1;
|
|
|
|
//bat_msg.serial_number = (battery_status.connected) ? battery_status.serial_number : 0;
|
|
|
|
//bat_msg.serial_number = (battery_status.connected) ? battery_status.serial_number : 0;
|
|
|
|
//bat_msg.capacity = (battery_status.connected) ? battery_status.capacity : 0;
|
|
|
|
//bat_msg.capacity = (battery_status.connected) ? battery_status.capacity : 0;
|
|
|
|