PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
battery.hpp
1/****************************************************************************
2 * Copyright (c) 2023-2024 PX4 Development Team.
3 * SPDX-License-Identifier: BSD-3-Clause
4 ****************************************************************************/
5
6#pragma once
7
8#include <Eigen/Eigen>
9#include <px4_msgs/msg/battery_status.hpp>
10#include <px4_ros2/common/context.hpp>
11#include <px4_ros2/utils/subscription.hpp>
12
13namespace px4_ros2
14{
24class Battery : public Subscription<px4_msgs::msg::BatteryStatus>
25{
26public:
27 explicit Battery(Context & context)
28 : Subscription<px4_msgs::msg::BatteryStatus>(context, "fmu/out/battery_status") {}
29
35 float voltageV() const
36 {
37 return last().voltage_v;
38 }
39
45 float currentA() const
46 {
47 return last().current_a;
48 }
49
56 {
57 return last().discharged_mah;
58 }
59
65 float remaningFraction() const
66 {
67 return last().remaining;
68 }
69
75 uint8_t cellCount() const
76 {
77 return last().cell_count;
78 }
79
85 Eigen::VectorXf cellVoltagesV() const
86 {
87 const px4_msgs::msg::BatteryStatus & battery = last();
88 const uint8_t cell_count = battery.cell_count;
89
90 if (cell_count == 0) {
91 RCLCPP_WARN_THROTTLE(
92 _node.get_logger(),
93 *_node.get_clock(), 1000, "Failed to retrieve battery cell voltage: cell count unknown.");
94 return Eigen::VectorXf();
95 }
96
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];
100 }
101
102 return cell_voltages;
103 }
104
105};
106
108} /* namespace px4_ros2 */
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