mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: correct comments on AP_OpticalFlow methods
This commit is contained in:
parent
0c943cac58
commit
22988ac585
|
@ -79,10 +79,10 @@ public:
|
|||
// quality - returns the surface quality as a measure from 0 ~ 255
|
||||
uint8_t quality() const { return _state.surface_quality; }
|
||||
|
||||
// raw - returns the raw movement from the sensor
|
||||
// flowRate - returns the raw movement from the sensor in rad/s
|
||||
const Vector2f& flowRate() const { return _state.flowRate; }
|
||||
|
||||
// velocity - returns the velocity in m/s
|
||||
// bodyRate - returns the IMU-adjusted movement in rad/s
|
||||
const Vector2f& bodyRate() const { return _state.bodyRate; }
|
||||
|
||||
// last_update() - returns system time of last sensor update
|
||||
|
|
Loading…
Reference in New Issue