mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 18:14:19 -03:00
AP_OpticalFlow: use const reference
saves stack space and cpu
This commit is contained in:
parent
f722ddf615
commit
047a09c391
@ -74,7 +74,7 @@ public:
|
||||
void setHIL(const struct OpticalFlow_state &state);
|
||||
|
||||
// return a 3D vector defining the position offset of the sensors focal point in metres relative to the body frame origin
|
||||
const Vector3f get_pos_offset(void) const {
|
||||
const Vector3f &get_pos_offset(void) const {
|
||||
return _pos_offset;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user