mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_SmartRTL: rename dataflash to logger
This commit is contained in:
parent
e9bb6a7d69
commit
15b89f37ef
@ -817,7 +817,7 @@ AP_SmartRTL::dist_point AP_SmartRTL::segment_segment_dist(const Vector3f &p1, co
|
|||||||
return {dP.length(), midpoint};
|
return {dP.length(), midpoint};
|
||||||
}
|
}
|
||||||
|
|
||||||
// de-activate SmartRTL, send warning to GCS and log to dataflash
|
// de-activate SmartRTL, send warning to GCS and logger
|
||||||
void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
|
void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
|
||||||
{
|
{
|
||||||
_active = false;
|
_active = false;
|
||||||
|
@ -155,7 +155,7 @@ private:
|
|||||||
// get the closest distance between 2 line segments and the point midway between the closest points
|
// get the closest distance between 2 line segments and the point midway between the closest points
|
||||||
static dist_point segment_segment_dist(const Vector3f& p1, const Vector3f& p2, const Vector3f& p3, const Vector3f& p4);
|
static dist_point segment_segment_dist(const Vector3f& p1, const Vector3f& p2, const Vector3f& p3, const Vector3f& p4);
|
||||||
|
|
||||||
// de-activate SmartRTL, send warning to GCS and log to dataflash
|
// de-activate SmartRTL, send warning to GCS and logger
|
||||||
void deactivate(SRTL_Actions action, const char *reason);
|
void deactivate(SRTL_Actions action, const char *reason);
|
||||||
|
|
||||||
// logging
|
// logging
|
||||||
|
Loading…
Reference in New Issue
Block a user