mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AP_Logger: VISP message gets velocity error field
This commit is contained in:
parent
31763424a3
commit
714975662d
@ -282,7 +282,7 @@ public:
|
|||||||
const RallyLocation &rally_point);
|
const RallyLocation &rally_point);
|
||||||
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
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, 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, uint8_t reset_counter);
|
||||||
void Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, 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_AOA_SSA(AP_AHRS &ahrs);
|
void Write_AOA_SSA(AP_AHRS &ahrs);
|
||||||
void Write_Beacon(AP_Beacon &beacon);
|
void Write_Beacon(AP_Beacon &beacon);
|
||||||
void Write_Proximity(AP_Proximity &proximity);
|
void Write_Proximity(AP_Proximity &proximity);
|
||||||
|
@ -930,7 +930,7 @@ void AP_Logger::Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms,
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Write visual velocity sensor data, velocity in NED meters per second
|
// 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, 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)
|
||||||
{
|
{
|
||||||
const struct log_VisualVelocity pkt_visualvel {
|
const struct log_VisualVelocity pkt_visualvel {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_VISUALVEL_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_VISUALVEL_MSG),
|
||||||
@ -940,6 +940,7 @@ void AP_Logger::Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms,
|
|||||||
vel_x : vel.x,
|
vel_x : vel.x,
|
||||||
vel_y : vel.y,
|
vel_y : vel.y,
|
||||||
vel_z : vel.z,
|
vel_z : vel.z,
|
||||||
|
vel_err : vel_err,
|
||||||
reset_counter : reset_counter
|
reset_counter : reset_counter
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt_visualvel, sizeof(log_VisualVelocity));
|
WriteBlock(&pkt_visualvel, sizeof(log_VisualVelocity));
|
||||||
|
@ -636,6 +636,7 @@ struct PACKED log_VisualVelocity {
|
|||||||
float vel_x;
|
float vel_x;
|
||||||
float vel_y;
|
float vel_y;
|
||||||
float vel_z;
|
float vel_z;
|
||||||
|
float vel_err;
|
||||||
uint8_t reset_counter;
|
uint8_t reset_counter;
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -2494,7 +2495,7 @@ struct PACKED log_Arm_Disarm {
|
|||||||
{ LOG_VISUALPOS_MSG, sizeof(log_VisualPosition), \
|
{ LOG_VISUALPOS_MSG, sizeof(log_VisualPosition), \
|
||||||
"VISP", "QQIffffffb", "TimeUS,RemTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw,ResetCnt", "sssmmmddh-", "FFC000000-" }, \
|
"VISP", "QQIffffffb", "TimeUS,RemTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw,ResetCnt", "sssmmmddh-", "FFC000000-" }, \
|
||||||
{ LOG_VISUALVEL_MSG, sizeof(log_VisualVelocity), \
|
{ LOG_VISUALVEL_MSG, sizeof(log_VisualVelocity), \
|
||||||
"VISV", "QQIfffb", "TimeUS,RemTimeUS,CTimeMS,VX,VY,VZ,ResetCnt", "sssnnn-", "FFC000-" }, \
|
"VISV", "QQIffffb", "TimeUS,RemTimeUS,CTimeMS,VX,VY,VZ,VErr,ResetCnt", "sssnnnn-", "FFC0000-" }, \
|
||||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), \
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), \
|
||||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEnn", "F-0000" }, \
|
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEnn", "F-0000" }, \
|
||||||
{ LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder), \
|
{ LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder), \
|
||||||
|
Loading…
Reference in New Issue
Block a user