mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GPS: use const reference
This commit is contained in:
parent
27cdf220de
commit
af332cb336
@ -313,10 +313,10 @@ public:
|
||||
float get_lag() const { return 0.2f; }
|
||||
|
||||
// return a 3D vector defining the offset of the GPS antenna in metres relative to the body frame origin
|
||||
const Vector3f get_antenna_offset(uint8_t instance) const {
|
||||
const Vector3f &get_antenna_offset(uint8_t instance) const {
|
||||
return _antenna_offset[instance];
|
||||
}
|
||||
const Vector3f get_antenna_offset(void) const {
|
||||
const Vector3f &get_antenna_offset(void) const {
|
||||
return _antenna_offset[primary_instance];
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user