Skip to content
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
2 changes: 1 addition & 1 deletion src/drivers/rc/crsf_rc/CrsfRc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ void CrsfRc::Run()
int32_t longitude = static_cast<int32_t>(round(sensor_gps.longitude_deg * 1e7));
uint16_t groundspeed = sensor_gps.vel_d_m_s / 3.6f * 10.f;
uint16_t gps_heading = math::degrees(sensor_gps.cog_rad) * 100.f;
uint16_t altitude = static_cast<int16_t>(sensor_gps.altitude_msl_m * 1e3) + 1000;
uint16_t altitude = static_cast<int16_t>(sensor_gps.altitude_msl_m) + 1000;
uint8_t num_satellites = sensor_gps.satellites_used;
this->SendTelemetryGps(latitude, longitude, groundspeed, gps_heading, altitude, num_satellites);
}
Expand Down