mirror of https://github.com/ArduPilot/ardupilot
AP_Follow: update FOLL log column names
VelN is easier to understand than VelX Also minor formatting fix
This commit is contained in:
parent
f53bfdbd38
commit
0834e7ae9b
|
@ -269,7 +269,7 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg)
|
||||||
|
|
||||||
_target_location.lat = packet.lat;
|
_target_location.lat = packet.lat;
|
||||||
_target_location.lng = packet.lon;
|
_target_location.lng = packet.lon;
|
||||||
|
|
||||||
// select altitude source based on FOLL_ALT_TYPE param
|
// select altitude source based on FOLL_ALT_TYPE param
|
||||||
if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
|
if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
|
||||||
// relative altitude
|
// relative altitude
|
||||||
|
@ -304,7 +304,7 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg)
|
||||||
|
|
||||||
// log lead's estimated vs reported position
|
// log lead's estimated vs reported position
|
||||||
DataFlash_Class::instance()->Log_Write("FOLL",
|
DataFlash_Class::instance()->Log_Write("FOLL",
|
||||||
"TimeUS,Lat,Lon,Alt,VelX,VelY,VelZ,LatE,LonE,AltE", // labels
|
"TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels
|
||||||
"sDUmnnnDUm", // units
|
"sDUmnnnDUm", // units
|
||||||
"F--B000--B", // mults
|
"F--B000--B", // mults
|
||||||
"QLLifffLLi", // fmt
|
"QLLifffLLi", // fmt
|
||||||
|
@ -342,7 +342,7 @@ bool AP_Follow::get_offsets_ned(Vector3f &offset) const
|
||||||
{
|
{
|
||||||
const Vector3f &off = _offset.get();
|
const Vector3f &off = _offset.get();
|
||||||
|
|
||||||
// if offsets are zero or type if NED, simply return offset vector
|
// if offsets are zero or type is NED, simply return offset vector
|
||||||
if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {
|
if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {
|
||||||
offset = off;
|
offset = off;
|
||||||
return true;
|
return true;
|
||||||
|
|
Loading…
Reference in New Issue