Provides access to the vehicle's battery status.
More...
#include <px4_ros2/vehicle_state/battery.hpp>
|
|
| Battery (Context &context) |
| |
| float | voltageV () const |
| | Get the vehicle's battery voltage. More...
|
| |
| float | currentA () const |
| | Get the vehicle's battery current. More...
|
| |
| float | dischargedCapacityMah () const |
| | Get the vehicle's battery cumulative discharged capacity. More...
|
| |
| float | remaningFraction () const |
| | Get the vehicle's battery remaining charge as a fraction. More...
|
| |
| uint8_t | cellCount () const |
| | Get the vehicle's battery cell count. More...
|
| |
| Eigen::VectorXf | cellVoltagesV () const |
| | Get the voltages of each cell in the vehicle's battery. More...
|
| |
|
| Subscription (Context &context, const std::string &topic) |
| |
| void | onUpdate (const UpdateCallback &callback) |
| | Add a callback to execute when receiving a new message. More...
|
| |
| const px4_msgs::msg::BatteryStatus & | last () const |
| | Get the last-received message. More...
|
| |
| const rclcpp::Time & | lastTime () const |
| | Get the receive-time of the last message. More...
|
| |
| bool | lastValid (const std::chrono::duration< int64_t, DurationT > max_delay=500ms) const |
| | Check whether the last message is still valid. To be valid, the message must have been received within a given time of the current time. More...
|
| |
Provides access to the vehicle's battery status.
◆ cellCount()
| uint8_t px4_ros2::Battery::cellCount |
( |
| ) |
const |
|
inline |
Get the vehicle's battery cell count.
- Returns
- the number of cells, 0 if unknown
◆ cellVoltagesV()
| Eigen::VectorXf px4_ros2::Battery::cellVoltagesV |
( |
| ) |
const |
|
inline |
Get the voltages of each cell in the vehicle's battery.
- Returns
- an Eigen vector containing the cell voltages. If the cell count is unknown, returns an empty vector.
◆ currentA()
| float px4_ros2::Battery::currentA |
( |
| ) |
const |
|
inline |
Get the vehicle's battery current.
- Returns
- the current [A], or -1 if unknown
◆ dischargedCapacityMah()
| float px4_ros2::Battery::dischargedCapacityMah |
( |
| ) |
const |
|
inline |
Get the vehicle's battery cumulative discharged capacity.
- Returns
- the discharged capacity [mAh], or -1 if unknown
◆ remaningFraction()
| float px4_ros2::Battery::remaningFraction |
( |
| ) |
const |
|
inline |
Get the vehicle's battery remaining charge as a fraction.
- Returns
- the remaining battery charge, 0.0 (empty) to 1.0 (full), or -1 if unknown.
◆ voltageV()
| float px4_ros2::Battery::voltageV |
( |
| ) |
const |
|
inline |
Get the vehicle's battery voltage.
- Returns
- the voltage [V], or 0 if unknown
The documentation for this class was generated from the following file:
- px4_ros2_cpp/include/px4_ros2/vehicle_state/battery.hpp