|
|
|
@ -1355,13 +1355,14 @@ void NavEKF3::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, fl
@@ -1355,13 +1355,14 @@ void NavEKF3::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, fl
|
|
|
|
|
* delAng is the XYZ angular rotation measured in body frame and relative to the inertial reference at timeStamp_ms (rad) |
|
|
|
|
* delTime is the time interval for the measurement of delPos and delAng (sec) |
|
|
|
|
* timeStamp_ms is the timestamp of the last image used to calculate delPos and delAng (msec) |
|
|
|
|
* delay_ms is the average delay of external nav system measurements relative to inertial measurements |
|
|
|
|
* posOffset is the XYZ body frame position of the camera focal point (m) |
|
|
|
|
*/ |
|
|
|
|
void NavEKF3::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset) |
|
|
|
|
void NavEKF3::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset) |
|
|
|
|
{ |
|
|
|
|
if (core) { |
|
|
|
|
for (uint8_t i=0; i<num_cores; i++) { |
|
|
|
|
core[i].writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset); |
|
|
|
|
core[i].writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, delay_ms, posOffset); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|