9 #include <px4_msgs/msg/battery_status.hpp>
10 #include <px4_ros2/common/context.hpp>
11 #include <px4_ros2/utils/subscription.hpp>
37 return last().voltage_v;
47 return last().current_a;
57 return last().discharged_mah;
67 return last().remaining;
77 return last().cell_count;
87 const px4_msgs::msg::BatteryStatus & battery =
last();
88 const uint8_t cell_count = battery.cell_count;
90 if (cell_count == 0) {
93 *_node.get_clock(), 1000,
"Failed to retrieve battery cell voltage: cell count unknown.");
94 return Eigen::VectorXf();
97 Eigen::VectorXf cell_voltages(cell_count);
98 for (uint8_t i = 0; i < cell_count; ++i) {
99 cell_voltages(i) = battery.voltage_cell_v[i];
102 return cell_voltages;
Provides access to the vehicle's battery status.
Definition: battery.hpp:25
uint8_t cellCount() const
Get the vehicle's battery cell count.
Definition: battery.hpp:75
float dischargedCapacityMah() const
Get the vehicle's battery cumulative discharged capacity.
Definition: battery.hpp:55
float currentA() const
Get the vehicle's battery current.
Definition: battery.hpp:45
float voltageV() const
Get the vehicle's battery voltage.
Definition: battery.hpp:35
float remaningFraction() const
Get the vehicle's battery remaining charge as a fraction.
Definition: battery.hpp:65
Eigen::VectorXf cellVoltagesV() const
Get the voltages of each cell in the vehicle's battery.
Definition: battery.hpp:85
Definition: context.hpp:20
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:23
const px4_msgs::msg::BatteryStatus & last() const
Get the last-received message.
Definition: subscription.hpp:58