Skip to content

Commit

Permalink
Telemetry and TelemetryServer improvements (#2511)
Browse files Browse the repository at this point in the history
* proto: update to latest main (1.2.1)

This fixes a regression with 1.2.0 regarding extra options.

* Add attitude and expanded fixed wing metrics for TelemetryServer

* Bug fix for ranges on attitude and heading messages

* Re-order FixedwingMetrics fields for backward compatibility

* PR feedback: altitude_msl -> absolute_altitude_m

* Proto update

* proto based on main

* Proto -> main

---------

Co-authored-by: Julian Oes <[email protected]>
Co-authored-by: Jon Reeves <[email protected]>
  • Loading branch information
3 people authored Feb 13, 2025
1 parent d9f97bc commit 72549f6
Show file tree
Hide file tree
Showing 17 changed files with 6,051 additions and 2,565 deletions.
2 changes: 1 addition & 1 deletion proto
3 changes: 3 additions & 0 deletions src/integration_tests/telemetry_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,7 +264,10 @@ void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity
void print_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
{
std::cout << "async Airspeed: " << fixedwing_metrics.airspeed_m_s << " m/s, "
<< "Groundspeed: " << fixedwing_metrics.groundspeed_m_s << " m/s, "
<< "Heading: " << fixedwing_metrics.heading_deg << " deg, "
<< "Throttle: " << fixedwing_metrics.throttle_percentage << " %, "
<< "Altitude: " << fixedwing_metrics.absolute_altitude_m << " m (MSL), "
<< "Climb: " << fixedwing_metrics.climb_rate_m_s << " m/s" << '\n';
_received_fixedwing_metrics = true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -813,6 +813,10 @@ class Telemetry : public PluginBase {
float(NAN)}; /**< @brief Current indicated airspeed (IAS) in metres per second */
float throttle_percentage{float(NAN)}; /**< @brief Current throttle setting (0 to 100) */
float climb_rate_m_s{float(NAN)}; /**< @brief Current climb rate in metres per second */
float groundspeed_m_s{float(NAN)}; /**< @brief Current groundspeed metres per second */
float heading_deg{
float(NAN)}; /**< @brief Current heading in compass units (0-360, 0=north) */
float absolute_altitude_m{float(NAN)}; /**< @brief Current altitude in metres (MSL) */
};

/**
Expand Down
11 changes: 10 additions & 1 deletion src/mavsdk/plugins/telemetry/telemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1322,7 +1322,13 @@ bool operator==(const Telemetry::FixedwingMetrics& lhs, const Telemetry::Fixedwi
((std::isnan(rhs.throttle_percentage) && std::isnan(lhs.throttle_percentage)) ||
rhs.throttle_percentage == lhs.throttle_percentage) &&
((std::isnan(rhs.climb_rate_m_s) && std::isnan(lhs.climb_rate_m_s)) ||
rhs.climb_rate_m_s == lhs.climb_rate_m_s);
rhs.climb_rate_m_s == lhs.climb_rate_m_s) &&
((std::isnan(rhs.groundspeed_m_s) && std::isnan(lhs.groundspeed_m_s)) ||
rhs.groundspeed_m_s == lhs.groundspeed_m_s) &&
((std::isnan(rhs.heading_deg) && std::isnan(lhs.heading_deg)) ||
rhs.heading_deg == lhs.heading_deg) &&
((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) ||
rhs.absolute_altitude_m == lhs.absolute_altitude_m);
}

std::ostream& operator<<(std::ostream& str, Telemetry::FixedwingMetrics const& fixedwing_metrics)
Expand All @@ -1332,6 +1338,9 @@ std::ostream& operator<<(std::ostream& str, Telemetry::FixedwingMetrics const& f
str << " airspeed_m_s: " << fixedwing_metrics.airspeed_m_s << '\n';
str << " throttle_percentage: " << fixedwing_metrics.throttle_percentage << '\n';
str << " climb_rate_m_s: " << fixedwing_metrics.climb_rate_m_s << '\n';
str << " groundspeed_m_s: " << fixedwing_metrics.groundspeed_m_s << '\n';
str << " heading_deg: " << fixedwing_metrics.heading_deg << '\n';
str << " absolute_altitude_m: " << fixedwing_metrics.absolute_altitude_m << '\n';
str << '}';
return str;
}
Expand Down
3 changes: 3 additions & 0 deletions src/mavsdk/plugins/telemetry/telemetry_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -994,7 +994,10 @@ void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)

Telemetry::FixedwingMetrics new_fixedwing_metrics;
new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed;
new_fixedwing_metrics.heading_deg = vfr_hud.heading;
new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt;
new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;

set_fixedwing_metrics(new_fixedwing_metrics);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -757,6 +757,10 @@ class TelemetryServer : public ServerPluginBase {
float(NAN)}; /**< @brief Current indicated airspeed (IAS) in metres per second */
float throttle_percentage{float(NAN)}; /**< @brief Current throttle setting (0 to 100) */
float climb_rate_m_s{float(NAN)}; /**< @brief Current climb rate in metres per second */
float groundspeed_m_s{float(NAN)}; /**< @brief Current groundspeed metres per second */
float heading_deg{
float(NAN)}; /**< @brief Current heading in compass units (0-360, 0=north) */
float absolute_altitude_m{float(NAN)}; /**< @brief Current altitude in metres (MSL) */
};

/**
Expand Down Expand Up @@ -1052,6 +1056,24 @@ class TelemetryServer : public ServerPluginBase {
*/
Result publish_distance_sensor(DistanceSensor distance_sensor) const;

/**
* @brief Publish to "attitude" updates.
*
* This function is blocking.
*
* @return Result of request.
*/
Result publish_attitude(EulerAngle angle, AngularVelocityBody angular_velocity) const;

/**
* @brief Publish to "Visual Flight Rules HUD" updates.
*
* This function is blocking.
*
* @return Result of request.
*/
Result publish_visual_flight_rules_hud(FixedwingMetrics fixed_wing_metrics) const;

/**
* @brief Copy constructor.
*/
Expand Down
23 changes: 22 additions & 1 deletion src/mavsdk/plugins/telemetry_server/telemetry_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,18 @@ TelemetryServer::publish_distance_sensor(DistanceSensor distance_sensor) const
return _impl->publish_distance_sensor(distance_sensor);
}

TelemetryServer::Result
TelemetryServer::publish_attitude(EulerAngle angle, AngularVelocityBody angular_velocity) const
{
return _impl->publish_attitude(angle, angular_velocity);
}

TelemetryServer::Result
TelemetryServer::publish_visual_flight_rules_hud(FixedwingMetrics fixed_wing_metrics) const
{
return _impl->publish_visual_flight_rules_hud(fixed_wing_metrics);
}

bool operator==(const TelemetryServer::Position& lhs, const TelemetryServer::Position& rhs)
{
return ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) ||
Expand Down Expand Up @@ -639,7 +651,13 @@ bool operator==(
((std::isnan(rhs.throttle_percentage) && std::isnan(lhs.throttle_percentage)) ||
rhs.throttle_percentage == lhs.throttle_percentage) &&
((std::isnan(rhs.climb_rate_m_s) && std::isnan(lhs.climb_rate_m_s)) ||
rhs.climb_rate_m_s == lhs.climb_rate_m_s);
rhs.climb_rate_m_s == lhs.climb_rate_m_s) &&
((std::isnan(rhs.groundspeed_m_s) && std::isnan(lhs.groundspeed_m_s)) ||
rhs.groundspeed_m_s == lhs.groundspeed_m_s) &&
((std::isnan(rhs.heading_deg) && std::isnan(lhs.heading_deg)) ||
rhs.heading_deg == lhs.heading_deg) &&
((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) ||
rhs.absolute_altitude_m == lhs.absolute_altitude_m);
}

std::ostream&
Expand All @@ -650,6 +668,9 @@ operator<<(std::ostream& str, TelemetryServer::FixedwingMetrics const& fixedwing
str << " airspeed_m_s: " << fixedwing_metrics.airspeed_m_s << '\n';
str << " throttle_percentage: " << fixedwing_metrics.throttle_percentage << '\n';
str << " climb_rate_m_s: " << fixedwing_metrics.climb_rate_m_s << '\n';
str << " groundspeed_m_s: " << fixedwing_metrics.groundspeed_m_s << '\n';
str << " heading_deg: " << fixedwing_metrics.heading_deg << '\n';
str << " absolute_altitude_m: " << fixedwing_metrics.absolute_altitude_m << '\n';
str << '}';
return str;
}
Expand Down
47 changes: 47 additions & 0 deletions src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -524,4 +524,51 @@ TelemetryServer::Result TelemetryServerImpl::publish_extended_sys_state(
TelemetryServer::Result::Unsupported;
}

TelemetryServer::Result TelemetryServerImpl::publish_attitude(
TelemetryServer::EulerAngle attitude, TelemetryServer::AngularVelocityBody angular_velocity)
{
return _server_component_impl->queue_message(
[&](MavlinkAddress mavlink_address, uint8_t channel) {
mavlink_message_t message;
mavlink_msg_attitude_pack_chan(
mavlink_address.system_id,
mavlink_address.component_id,
channel,
&message,
static_cast<uint32_t>(attitude.timestamp_us / 1000.F),
attitude.roll_deg * M_PI / 180.F,
attitude.pitch_deg * M_PI / 180.F,
attitude.yaw_deg * M_PI / 180.F,
angular_velocity.roll_rad_s,
angular_velocity.pitch_rad_s,
angular_velocity.yaw_rad_s);
return message;
}) ?
TelemetryServer::Result::Success :
TelemetryServer::Result::Unsupported;
}

TelemetryServer::Result TelemetryServerImpl::publish_visual_flight_rules_hud(
TelemetryServer::FixedwingMetrics fixed_wing_metrics)
{
return _server_component_impl->queue_message(
[&](MavlinkAddress mavlink_address, uint8_t channel) {
mavlink_message_t message;
mavlink_msg_vfr_hud_pack_chan(
mavlink_address.system_id,
mavlink_address.component_id,
channel,
&message,
fixed_wing_metrics.airspeed_m_s,
fixed_wing_metrics.groundspeed_m_s,
static_cast<uint16_t>(std::round(fixed_wing_metrics.heading_deg)),
static_cast<uint16_t>(std::round(fixed_wing_metrics.throttle_percentage)),
fixed_wing_metrics.absolute_altitude_m,
fixed_wing_metrics.climb_rate_m_s);
return message;
}) ?
TelemetryServer::Result::Success :
TelemetryServer::Result::Unsupported;
}

} // namespace mavsdk
7 changes: 7 additions & 0 deletions src/mavsdk/plugins/telemetry_server/telemetry_server_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,13 @@ class TelemetryServerImpl : public ServerPluginImplBase {
TelemetryServer::Result publish_extended_sys_state(
TelemetryServer::VtolState vtol_state, TelemetryServer::LandedState landed_state);

TelemetryServer::Result publish_attitude(
TelemetryServer::EulerAngle attitude,
TelemetryServer::AngularVelocityBody angular_velocity);

TelemetryServer::Result
publish_visual_flight_rules_hud(TelemetryServer::FixedwingMetrics fixed_wing_metrics);

private:
bool _send_home();

Expand Down
Loading

0 comments on commit 72549f6

Please sign in to comment.