mirror of https://github.com/ArduPilot/ardupilot
AP_ADSB: fix getting a copy rather than a reference
These have been caught by making constructors private and enforcing calling a create() method to create objects are supposed to be statically allocated only. The Vector3f reference was just nearby and was a change copied from similar PR from Peter Barker (#6873).
This commit is contained in:
parent
e23a2c5254
commit
eaa603b05c
|
@ -462,8 +462,8 @@ void AP_ADSB::send_adsb_vehicle(const mavlink_channel_t chan)
|
||||||
|
|
||||||
void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
|
void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
AP_GPS gps = _ahrs.get_gps();
|
const AP_GPS &gps = _ahrs.get_gps();
|
||||||
Vector3f gps_velocity = gps.velocity();
|
const Vector3f &gps_velocity = gps.velocity();
|
||||||
|
|
||||||
int32_t latitude = _my_loc.lat;
|
int32_t latitude = _my_loc.lat;
|
||||||
int32_t longitude = _my_loc.lng;
|
int32_t longitude = _my_loc.lng;
|
||||||
|
@ -506,7 +506,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
|
||||||
const uint64_t gps_time = gps.time_epoch_usec();
|
const uint64_t gps_time = gps.time_epoch_usec();
|
||||||
const uint32_t utcTime = gps_time / 1000000ULL;
|
const uint32_t utcTime = gps_time / 1000000ULL;
|
||||||
|
|
||||||
AP_Baro baro = _ahrs.get_baro();
|
const AP_Baro &baro = _ahrs.get_baro();
|
||||||
int32_t altPres = INT_MAX;
|
int32_t altPres = INT_MAX;
|
||||||
if (baro.healthy()) {
|
if (baro.healthy()) {
|
||||||
// Altitude difference between 101325 (Pascals) and current pressure. Result in millimeters
|
// Altitude difference between 101325 (Pascals) and current pressure. Result in millimeters
|
||||||
|
@ -578,7 +578,7 @@ uint32_t AP_ADSB::genICAO(const Location_Class &loc)
|
||||||
{
|
{
|
||||||
// gps_time is not seconds since UTC midnight, but it is an equivalent random number
|
// gps_time is not seconds since UTC midnight, but it is an equivalent random number
|
||||||
// TODO: use UTC time instead of GPS time
|
// TODO: use UTC time instead of GPS time
|
||||||
AP_GPS gps = _ahrs.get_gps();
|
const AP_GPS &gps = _ahrs.get_gps();
|
||||||
const uint64_t gps_time = gps.time_epoch_usec();
|
const uint64_t gps_time = gps.time_epoch_usec();
|
||||||
|
|
||||||
uint32_t timeSum = 0;
|
uint32_t timeSum = 0;
|
||||||
|
|
Loading…
Reference in New Issue