Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_RCTelemetry: Fix Baro and Vario values #28478

Merged
merged 1 commit into from
Nov 5, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -975,7 +975,7 @@ int8_t AP_CRSF_Telem::get_vertical_speed_packed()
// prepare vario data
void AP_CRSF_Telem::calc_baro_vario()
{
_telem.bcast.baro_vario.altitude_packed = get_altitude_packed();
_telem.bcast.baro_vario.altitude_packed = htobe16(get_altitude_packed());
_telem.bcast.baro_vario.vertical_speed_packed = get_vertical_speed_packed();

_telem_size = sizeof(BaroVarioFrame);
Expand All @@ -987,7 +987,7 @@ void AP_CRSF_Telem::calc_baro_vario()
// prepare vario data
void AP_CRSF_Telem::calc_vario()
{
_telem.bcast.vario.v_speed = int16_t(get_vspeed_ms() * 100.0f);
_telem.bcast.vario.v_speed = htobe16(int16_t(get_vspeed_ms() * 100.0f));
_telem_size = sizeof(VarioFrame);
_telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_VARIO;

Expand Down
Loading