mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
InertialSensor: fix name of get_delta_velocity method
This commit is contained in:
parent
cd9f62328e
commit
9d81856580
@ -135,7 +135,7 @@ public:
|
|||||||
float get_delta_velocity_dt(uint8_t i) const {
|
float get_delta_velocity_dt(uint8_t i) const {
|
||||||
return _delta_velocity_dt[i];
|
return _delta_velocity_dt[i];
|
||||||
}
|
}
|
||||||
float get_delta_velocity() const { return get_delta_velocity_dt(_primary_accel); }
|
float get_delta_velocity_dt() const { return get_delta_velocity_dt(_primary_accel); }
|
||||||
|
|
||||||
/// Fetch the current accelerometer values
|
/// Fetch the current accelerometer values
|
||||||
///
|
///
|
||||||
|
Loading…
Reference in New Issue
Block a user