mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Logger: VISP and VISV get ignored field
This commit is contained in:
parent
8e8b396afe
commit
d9b90bf19f
@ -279,8 +279,8 @@ public:
|
||||
uint8_t sequence,
|
||||
const RallyLocation &rally_point);
|
||||
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
||||
void Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float pos_err, float ang_err, uint8_t reset_counter);
|
||||
void Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, float vel_err, uint8_t reset_counter);
|
||||
void Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float pos_err, float ang_err, uint8_t reset_counter, bool ignored);
|
||||
void Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, float vel_err, uint8_t reset_counter, bool ignored);
|
||||
void Write_AOA_SSA(AP_AHRS &ahrs);
|
||||
void Write_Beacon(AP_Beacon &beacon);
|
||||
void Write_Proximity(AP_Proximity &proximity);
|
||||
|
@ -930,7 +930,7 @@ void AP_Logger::Write_VisualOdom(float time_delta, const Vector3f &angle_delta,
|
||||
}
|
||||
|
||||
// Write visual position sensor data. x,y,z are in meters, angles are in degrees
|
||||
void AP_Logger::Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float pos_err, float ang_err, uint8_t reset_counter)
|
||||
void AP_Logger::Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float pos_err, float ang_err, uint8_t reset_counter, bool ignored)
|
||||
{
|
||||
const struct log_VisualPosition pkt_visualpos {
|
||||
LOG_PACKET_HEADER_INIT(LOG_VISUALPOS_MSG),
|
||||
@ -945,13 +945,14 @@ void AP_Logger::Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms,
|
||||
yaw : yaw,
|
||||
pos_err : pos_err,
|
||||
ang_err : ang_err,
|
||||
reset_counter : reset_counter
|
||||
reset_counter : reset_counter,
|
||||
ignored : (uint8_t)ignored
|
||||
};
|
||||
WriteBlock(&pkt_visualpos, sizeof(log_VisualPosition));
|
||||
}
|
||||
|
||||
// Write visual velocity sensor data, velocity in NED meters per second
|
||||
void AP_Logger::Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, float vel_err, uint8_t reset_counter)
|
||||
void AP_Logger::Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, float vel_err, uint8_t reset_counter, bool ignored)
|
||||
{
|
||||
const struct log_VisualVelocity pkt_visualvel {
|
||||
LOG_PACKET_HEADER_INIT(LOG_VISUALVEL_MSG),
|
||||
@ -962,7 +963,8 @@ void AP_Logger::Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms,
|
||||
vel_y : vel.y,
|
||||
vel_z : vel.z,
|
||||
vel_err : vel_err,
|
||||
reset_counter : reset_counter
|
||||
reset_counter : reset_counter,
|
||||
ignored : (uint8_t)ignored
|
||||
};
|
||||
WriteBlock(&pkt_visualvel, sizeof(log_VisualVelocity));
|
||||
}
|
||||
|
@ -648,6 +648,7 @@ struct PACKED log_VisualPosition {
|
||||
float pos_err; // meters
|
||||
float ang_err; // radians
|
||||
uint8_t reset_counter;
|
||||
uint8_t ignored;
|
||||
};
|
||||
|
||||
struct PACKED log_VisualVelocity {
|
||||
@ -660,6 +661,7 @@ struct PACKED log_VisualVelocity {
|
||||
float vel_z;
|
||||
float vel_err;
|
||||
uint8_t reset_counter;
|
||||
uint8_t ignored;
|
||||
};
|
||||
|
||||
struct PACKED log_ekfBodyOdomDebug {
|
||||
@ -2268,7 +2270,8 @@ struct PACKED log_PSC {
|
||||
// @Field: Yaw: Yaw angle
|
||||
// @Field: PErr: Position estimate error
|
||||
// @Field: AErr: Attitude estimate error
|
||||
// @Field: RstCnt: Position reset counter
|
||||
// @Field: Rst: Position reset counter
|
||||
// @Field: Ign: Ignored
|
||||
|
||||
// @LoggerMessage: VISV
|
||||
// @Description: Vision Velocity
|
||||
@ -2279,7 +2282,8 @@ struct PACKED log_PSC {
|
||||
// @Field: VY: Velocity Y-axis (East-West)
|
||||
// @Field: VZ: Velocity Z-axis (Down-Up)
|
||||
// @Field: VErr: Velocity estimate error
|
||||
// @Field: RstCnt: Velocity reset counter
|
||||
// @Field: Rst: Velocity reset counter
|
||||
// @Field: Ign: Ignored
|
||||
|
||||
// @LoggerMessage: WENC
|
||||
// @Description: Wheel encoder measurements
|
||||
@ -2685,9 +2689,9 @@ struct PACKED log_PSC {
|
||||
{ LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \
|
||||
"VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \
|
||||
{ LOG_VISUALPOS_MSG, sizeof(log_VisualPosition), \
|
||||
"VISP", "QQIffffffffB", "TimeUS,RTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw,PErr,AErr,RstCnt", "sssmmmddhmd-", "FFC00000000-" }, \
|
||||
"VISP", "QQIffffffffBB", "TimeUS,RTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw,PErr,AErr,Rst,Ign", "sssmmmddhmd--", "FFC00000000--" }, \
|
||||
{ LOG_VISUALVEL_MSG, sizeof(log_VisualVelocity), \
|
||||
"VISV", "QQIffffB", "TimeUS,RTimeUS,CTimeMS,VX,VY,VZ,VErr,RstCnt", "sssnnnn-", "FFC0000-" }, \
|
||||
"VISV", "QQIffffBB", "TimeUS,RTimeUS,CTimeMS,VX,VY,VZ,VErr,Rst,Ign", "sssnnnn--", "FFC0000--" }, \
|
||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), \
|
||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEnn", "F-0000" }, \
|
||||
{ LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder), \
|
||||
|
Loading…
Reference in New Issue
Block a user