mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_AHRS: rename dataflash to logger
This commit is contained in:
parent
966b2652fb
commit
a577223ac6
@ -472,24 +472,22 @@ Vector2f AP_AHRS::rotate_body_to_earth2D(const Vector2f &bf) const
|
||||
bf.x * _sin_yaw + bf.y * _cos_yaw);
|
||||
}
|
||||
|
||||
// log ahrs home and EKF origin to dataflash
|
||||
// log ahrs home and EKF origin
|
||||
void AP_AHRS::Log_Write_Home_And_Origin()
|
||||
{
|
||||
AP_Logger *df = AP_Logger::get_singleton();
|
||||
if (df == nullptr) {
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger == nullptr) {
|
||||
return;
|
||||
}
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
// log ekf origin if set
|
||||
Location ekf_orig;
|
||||
if (get_origin(ekf_orig)) {
|
||||
df->Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
||||
logger->Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
||||
}
|
||||
#endif
|
||||
|
||||
// log ahrs home if set
|
||||
if (home_is_set()) {
|
||||
df->Write_Origin(LogOriginType::ahrs_home, _home);
|
||||
logger->Write_Origin(LogOriginType::ahrs_home, _home);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
*
|
||||
* AHRS system using DCM matrices
|
||||
*
|
||||
* Based on DCM code by Doug Weibel, Jordi Muñoz and Jose Julio. DIYDrones.com
|
||||
* Based on DCM code by Doug Weibel, Jordi Munoz and Jose Julio. DIYDrones.com
|
||||
*
|
||||
* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
|
||||
|
||||
@ -286,7 +286,7 @@ AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result)
|
||||
* to approximations rather than identities. In effect, the axes in the two frames of reference no
|
||||
* longer describe a rigid body. Fortunately, numerical error accumulates very slowly, so it is a
|
||||
* simple matter to stay ahead of it.
|
||||
* We call the process of enforcing the orthogonality conditions ÒrenormalizationÓ.
|
||||
* We call the process of enforcing the orthogonality conditions: renormalization.
|
||||
*/
|
||||
void
|
||||
AP_AHRS_DCM::normalize(void)
|
||||
@ -1051,7 +1051,6 @@ bool AP_AHRS_DCM::set_home(const Location &loc)
|
||||
_home = tmp;
|
||||
_home_is_set = true;
|
||||
|
||||
// log ahrs home and ekf origin dataflash
|
||||
Log_Write_Home_And_Origin();
|
||||
|
||||
// send new home and ekf origin to GCS
|
||||
|
Loading…
Reference in New Issue
Block a user