Skip to content

Commit 73f458c

Browse files
authored
Merge pull request #2524 from aminballoon/pr-update-Battery-TimeRemain&Function
Update Battery Remaining Time and Battery Function
2 parents a030c71 + b5a21c5 commit 73f458c

File tree

12 files changed

+777
-353
lines changed

12 files changed

+777
-353
lines changed

docs/en/cpp/api_reference/classmavsdk_1_1_telemetry.md

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,7 @@ struct [Wind](structmavsdk_1_1_telemetry_1_1_wind.md)
7878
Type | Description
7979
--- | ---
8080
enum [FixType](#classmavsdk_1_1_telemetry_1a548213e1b26615d7b6d1b0b3934639de) | GPS fix type.
81+
enum [BatteryFunction](#classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60) | [Battery](structmavsdk_1_1_telemetry_1_1_battery.md) function type.
8182
enum [FlightMode](#classmavsdk_1_1_telemetry_1a8317d953a82a23654db6f14509acb4fe) | Flight modes.
8283
enum [StatusTextType](#classmavsdk_1_1_telemetry_1ada3ebb336abad223a98bc2a625e0e7d8) | Status types.
8384
enum [LandedState](#classmavsdk_1_1_telemetry_1ac6639935bc3b35b1da553cde41e8f046) | Landed State enumeration.
@@ -1074,6 +1075,20 @@ Value | Description
10741075
<span id="classmavsdk_1_1_telemetry_1a548213e1b26615d7b6d1b0b3934639dea1eacb557d24c49af2ec6832c5fc32413"></span> `RtkFloat` | RTK float, 3D position.
10751076
<span id="classmavsdk_1_1_telemetry_1a548213e1b26615d7b6d1b0b3934639dea9effa0afed44833d540fec2c57e67426"></span> `RtkFixed` | RTK Fixed, 3D position.
10761077

1078+
### enum BatteryFunction {#classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60}
1079+
1080+
1081+
[Battery](structmavsdk_1_1_telemetry_1_1_battery.md) function type.
1082+
1083+
1084+
Value | Description
1085+
--- | ---
1086+
<span id="classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60a88183b946cc5f0e8c96b2e66e1c74a7e"></span> `Unknown` | [Battery](structmavsdk_1_1_telemetry_1_1_battery.md) function is unknown.
1087+
<span id="classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60ab1c94ca2fbc3e78fc30069c8d0f01680"></span> `All` | [Battery](structmavsdk_1_1_telemetry_1_1_battery.md) supports all flight systems.
1088+
<span id="classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60ae93e4a139c6304e9f1b4757fc8b7f169"></span> `Propulsion` | [Battery](structmavsdk_1_1_telemetry_1_1_battery.md) for the propulsion system.
1089+
<span id="classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60a0035c3a4fba659233a189e32e1849421"></span> `Avionics` | Avionics battery.
1090+
<span id="classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60a00f4e5788aab6d3546bb433842dbbefc"></span> `Payload` | Payload battery.
1091+
10771092
### enum FlightMode {#classmavsdk_1_1_telemetry_1a8317d953a82a23654db6f14509acb4fe}
10781093

10791094

docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_battery.md

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,10 @@ float [capacity_consumed_ah](#structmavsdk_1_1_telemetry_1_1_battery_1a3593f72c6
2222

2323
float [remaining_percent](#structmavsdk_1_1_telemetry_1_1_battery_1aec821550739844e0fa3fe18f91e6fda7) { float(NAN)} - Estimated battery remaining (range: 0 to 100)
2424

25+
float [time_remaining_s](#structmavsdk_1_1_telemetry_1_1_battery_1a9dd00470568d20ccda1b502f8ddf4ff1) {float(NAN)} - Estimated battery usage time remaining.
26+
27+
[BatteryFunction](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1adf751b819a1a38fc2b02442b5d5dae60) [battery_function](#structmavsdk_1_1_telemetry_1_1_battery_1a45654c797ef33bb134ac30313b73098c) {} - Function of the battery.
28+
2529

2630
## Field Documentation
2731

@@ -85,3 +89,23 @@ float mavsdk::Telemetry::Battery::remaining_percent { float(NAN)}
8589

8690
Estimated battery remaining (range: 0 to 100)
8791

92+
93+
### time_remaining_s {#structmavsdk_1_1_telemetry_1_1_battery_1a9dd00470568d20ccda1b502f8ddf4ff1}
94+
95+
```cpp
96+
float mavsdk::Telemetry::Battery::time_remaining_s {float(NAN)}
97+
```
98+
99+
100+
Estimated battery usage time remaining.
101+
102+
103+
### battery_function {#structmavsdk_1_1_telemetry_1_1_battery_1a45654c797ef33bb134ac30313b73098c}
104+
105+
```cpp
106+
BatteryFunction mavsdk::Telemetry::Battery::battery_function {}
107+
```
108+
109+
110+
Function of the battery.
111+

examples/battery/CMakeLists.txt

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,21 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON)
55

66
project(battery)
77

8-
add_executable(battery
9-
battery.cpp
8+
add_executable(publish_battery
9+
publish_battery.cpp
10+
)
11+
12+
add_executable(subscribe_battery
13+
subscribe_battery.cpp
1014
)
1115

1216
find_package(MAVSDK REQUIRED)
1317

14-
target_link_libraries(battery
18+
target_link_libraries(publish_battery
19+
MAVSDK::mavsdk
20+
)
21+
22+
target_link_libraries(subscribe_battery
1523
MAVSDK::mavsdk
1624
)
1725

File renamed without changes.
Lines changed: 91 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,91 @@
1+
//
2+
// Example for subscribe Battery data via MAVSDK
3+
//
4+
// Author: PannapatC <Github: Aminballoon>
5+
6+
#include <mavsdk/mavsdk.h>
7+
#include <mavsdk/plugins/telemetry/telemetry.h>
8+
#include <iostream>
9+
#include <chrono>
10+
#include <thread>
11+
#include <atomic>
12+
#include <csignal>
13+
14+
// Global atomic flag to indicate if the program should exit
15+
std::atomic<bool> should_exit{false};
16+
17+
// Signal handler for Ctrl+C
18+
void signal_handler(int signal)
19+
{
20+
if (signal == SIGINT) {
21+
std::cout << "\nCtrl+C pressed. Exiting..." << std::endl;
22+
should_exit.store(true);
23+
}
24+
}
25+
26+
int main(int argc, char** argv)
27+
{
28+
// Check for connection string argument
29+
if (argc != 2) {
30+
std::cerr << "Usage: " << argv[0] << " <connection_url>" << std::endl;
31+
return 1;
32+
}
33+
34+
// Initialize MAVSDK with GroundStation component type
35+
mavsdk::Mavsdk mavsdk{mavsdk::Mavsdk::Configuration{mavsdk::ComponentType::GroundStation}};
36+
37+
// Add connection
38+
mavsdk::ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]);
39+
if (connection_result != mavsdk::ConnectionResult::Success) {
40+
std::cerr << "Connection failed: " << connection_result << std::endl;
41+
return 1;
42+
}
43+
44+
// Wait for the system to connect
45+
std::cout << "Waiting for system to connect..." << std::endl;
46+
while (mavsdk.systems().size() == 0) {
47+
std::this_thread::sleep_for(std::chrono::seconds(1));
48+
}
49+
50+
// Get the connected system
51+
auto system = mavsdk.systems().at(0);
52+
if (!system->is_connected()) {
53+
std::cerr << "System not connected" << std::endl;
54+
return 1;
55+
}
56+
57+
// Instantiate the Telemetry plugin
58+
auto telemetry = mavsdk::Telemetry{system};
59+
60+
// Callback for battery updates
61+
auto battery_callback = [](mavsdk::Telemetry::Battery battery) {
62+
std::cout << "Battery ID: " << battery.id << " \n"
63+
<< "Battery Temp: " << battery.temperature_degc << " degc\n"
64+
<< "Battery Voltage: " << battery.voltage_v << " v\n"
65+
<< "Battery Current: " << battery.current_battery_a << " a\n"
66+
<< "Battery Capacity Consumed: " << battery.capacity_consumed_ah << " ah\n"
67+
<< "Battery Remaining Percent: " << battery.remaining_percent << " %\n"
68+
<< "Battery Remaining Time: " << battery.time_remaining_s << " s\n"
69+
<< "Battery Function: " << battery.battery_function << "\n"
70+
<< std::endl;
71+
};
72+
73+
// Subscribe to battery updates
74+
auto battery_handle = telemetry.subscribe_battery(battery_callback);
75+
76+
// Register the signal handler for Ctrl+C
77+
std::signal(SIGINT, signal_handler);
78+
79+
// Main loop
80+
std::cout << "Listening for battery updates. Press Ctrl+C to exit..." << std::endl;
81+
while (!should_exit.load()) {
82+
std::this_thread::sleep_for(std::chrono::milliseconds(500));
83+
}
84+
85+
// Unsubscribe from battery updates
86+
telemetry.unsubscribe_battery(battery_handle);
87+
std::cout << "Unsubscribed from battery updates." << std::endl;
88+
89+
std::cout << "Exiting program." << std::endl;
90+
return 0;
91+
}

proto

src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,25 @@ class Telemetry : public PluginBase {
7979
*/
8080
friend std::ostream& operator<<(std::ostream& str, Telemetry::FixType const& fix_type);
8181

82+
/**
83+
* @brief Battery function type.
84+
*/
85+
enum class BatteryFunction {
86+
Unknown, /**< @brief Battery function is unknown. */
87+
All, /**< @brief Battery supports all flight systems. */
88+
Propulsion, /**< @brief Battery for the propulsion system. */
89+
Avionics, /**< @brief Avionics battery. */
90+
Payload, /**< @brief Payload battery. */
91+
};
92+
93+
/**
94+
* @brief Stream operator to print information about a `Telemetry::BatteryFunction`.
95+
*
96+
* @return A reference to the stream.
97+
*/
98+
friend std::ostream&
99+
operator<<(std::ostream& str, Telemetry::BatteryFunction const& battery_function);
100+
82101
/**
83102
* @brief Flight modes.
84103
*
@@ -383,6 +402,8 @@ class Telemetry : public PluginBase {
383402
consumption estimate */
384403
float remaining_percent{
385404
float(NAN)}; /**< @brief Estimated battery remaining (range: 0 to 100) */
405+
float time_remaining_s{float(NAN)}; /**< @brief Estimated battery usage time remaining */
406+
BatteryFunction battery_function{}; /**< @brief Function of the battery */
386407
};
387408

388409
/**

src/mavsdk/plugins/telemetry/telemetry.cpp

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -982,7 +982,10 @@ bool operator==(const Telemetry::Battery& lhs, const Telemetry::Battery& rhs)
982982
((std::isnan(rhs.capacity_consumed_ah) && std::isnan(lhs.capacity_consumed_ah)) ||
983983
rhs.capacity_consumed_ah == lhs.capacity_consumed_ah) &&
984984
((std::isnan(rhs.remaining_percent) && std::isnan(lhs.remaining_percent)) ||
985-
rhs.remaining_percent == lhs.remaining_percent);
985+
rhs.remaining_percent == lhs.remaining_percent) &&
986+
((std::isnan(rhs.time_remaining_s) && std::isnan(lhs.time_remaining_s)) ||
987+
rhs.time_remaining_s == lhs.time_remaining_s) &&
988+
(rhs.battery_function == lhs.battery_function);
986989
}
987990

988991
std::ostream& operator<<(std::ostream& str, Telemetry::Battery const& battery)
@@ -995,6 +998,8 @@ std::ostream& operator<<(std::ostream& str, Telemetry::Battery const& battery)
995998
str << " current_battery_a: " << battery.current_battery_a << '\n';
996999
str << " capacity_consumed_ah: " << battery.capacity_consumed_ah << '\n';
9971000
str << " remaining_percent: " << battery.remaining_percent << '\n';
1001+
str << " time_remaining_s: " << battery.time_remaining_s << '\n';
1002+
str << " battery_function: " << battery.battery_function << '\n';
9981003
str << '}';
9991004
return str;
10001005
}
@@ -1588,6 +1593,24 @@ std::ostream& operator<<(std::ostream& str, Telemetry::FixType const& fix_type)
15881593
}
15891594
}
15901595

1596+
std::ostream& operator<<(std::ostream& str, Telemetry::BatteryFunction const& battery_function)
1597+
{
1598+
switch (battery_function) {
1599+
case Telemetry::BatteryFunction::Unknown:
1600+
return str << "Unknown";
1601+
case Telemetry::BatteryFunction::All:
1602+
return str << "All";
1603+
case Telemetry::BatteryFunction::Propulsion:
1604+
return str << "Propulsion";
1605+
case Telemetry::BatteryFunction::Avionics:
1606+
return str << "Avionics";
1607+
case Telemetry::BatteryFunction::Payload:
1608+
return str << "Payload";
1609+
default:
1610+
return str << "Unknown";
1611+
}
1612+
}
1613+
15911614
std::ostream& operator<<(std::ostream& str, Telemetry::FlightMode const& flight_mode)
15921615
{
15931616
switch (flight_mode) {

src/mavsdk/plugins/telemetry/telemetry_impl.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1155,7 +1155,30 @@ void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
11551155
new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
11561156
static_cast<float>(NAN) :
11571157
bat_status.current_consumed * 1e-3f; // mAh to Ah
1158+
new_battery.time_remaining_s =
1159+
(bat_status.time_remaining == 0 ? static_cast<float>(NAN) : bat_status.time_remaining);
11581160

1161+
Telemetry::BatteryFunction battery_function;
1162+
switch (bat_status.battery_function) {
1163+
case MAV_BATTERY_FUNCTION_ALL:
1164+
battery_function = Telemetry::BatteryFunction::All;
1165+
break;
1166+
case MAV_BATTERY_FUNCTION_PROPULSION:
1167+
battery_function = Telemetry::BatteryFunction::Propulsion;
1168+
break;
1169+
case MAV_BATTERY_FUNCTION_AVIONICS:
1170+
battery_function = Telemetry::BatteryFunction::Avionics;
1171+
break;
1172+
case MAV_BATTERY_FUNCTION_PAYLOAD:
1173+
battery_function = Telemetry::BatteryFunction::Payload;
1174+
break;
1175+
case MAV_BATTERY_FUNCTION_UNKNOWN:
1176+
// Fallthrough
1177+
default:
1178+
battery_function = Telemetry::BatteryFunction::Unknown;
1179+
break;
1180+
}
1181+
new_battery.battery_function = battery_function;
11591182
set_battery(new_battery);
11601183

11611184
{

0 commit comments

Comments
 (0)