AP_Math: clarify get_vel_correction_for_sensor_offset comment

This commit is contained in:
Randy Mackay 2020-05-29 10:14:54 +09:00
parent 4639e8a698
commit bdb67532b0
2 changed files with 2 additions and 0 deletions

View File

@ -340,6 +340,7 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2)
/*
* return a velocity correction (in m/s in NED) for a sensor's position given it's position offsets
* this correction should be added to the sensor NED measurement
* sensor_offset_bf is in meters in body frame (Foward, Right, Down)
* rot_ef_to_bf is a rotation matrix to rotate from earth-frame (NED) to body frame
* angular_rate is rad/sec

View File

@ -279,6 +279,7 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2) WARN_IF_UNUSED;
/*
* return a velocity correction (in m/s in NED) for a sensor's position given it's position offsets
* this correction should be added to the sensor NED measurement
* sensor_offset_bf is in meters in body frame (Foward, Right, Down)
* rot_ef_to_bf is a rotation matrix to rotate from earth-frame (NED) to body frame
* angular_rate is rad/sec