mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Logger: VISP msg adds reset_counter
This commit is contained in:
parent
fb7e68c53a
commit
4f639481c1
@ -281,7 +281,7 @@ public:
|
|||||||
uint8_t sequence,
|
uint8_t sequence,
|
||||||
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);
|
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_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);
|
||||||
|
@ -915,7 +915,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
|
// 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)
|
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, uint8_t reset_counter)
|
||||||
{
|
{
|
||||||
const struct log_VisualPosition pkt_visualpos {
|
const struct log_VisualPosition pkt_visualpos {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_VISUALPOS_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_VISUALPOS_MSG),
|
||||||
@ -927,7 +927,8 @@ void AP_Logger::Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms,
|
|||||||
pos_z : z,
|
pos_z : z,
|
||||||
roll : roll,
|
roll : roll,
|
||||||
pitch : pitch,
|
pitch : pitch,
|
||||||
yaw : yaw
|
yaw : yaw,
|
||||||
|
reset_counter : reset_counter
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt_visualpos, sizeof(log_VisualPosition));
|
WriteBlock(&pkt_visualpos, sizeof(log_VisualPosition));
|
||||||
}
|
}
|
||||||
|
@ -662,6 +662,7 @@ struct PACKED log_VisualPosition {
|
|||||||
float roll; // degrees
|
float roll; // degrees
|
||||||
float pitch; // degrees
|
float pitch; // degrees
|
||||||
float yaw; // degrees
|
float yaw; // degrees
|
||||||
|
uint8_t reset_counter;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_ekfBodyOdomDebug {
|
struct PACKED log_ekfBodyOdomDebug {
|
||||||
@ -2020,6 +2021,7 @@ struct PACKED log_Arm_Disarm {
|
|||||||
// @Field: Roll: Roll lean angle
|
// @Field: Roll: Roll lean angle
|
||||||
// @Field: Pitch: Pitch lean angle
|
// @Field: Pitch: Pitch lean angle
|
||||||
// @Field: Yaw: Yaw angle
|
// @Field: Yaw: Yaw angle
|
||||||
|
// @Field: ResetCnt: Position reset counter
|
||||||
|
|
||||||
// @LoggerMessage: WENC
|
// @LoggerMessage: WENC
|
||||||
// @Description: Wheel encoder measurements
|
// @Description: Wheel encoder measurements
|
||||||
@ -2250,7 +2252,7 @@ struct PACKED log_Arm_Disarm {
|
|||||||
{ LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \
|
{ LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \
|
||||||
"VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \
|
"VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \
|
||||||
{ LOG_VISUALPOS_MSG, sizeof(log_VisualPosition), \
|
{ LOG_VISUALPOS_MSG, sizeof(log_VisualPosition), \
|
||||||
"VISP", "QQIffffff", "TimeUS,RemTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw", "sssmmmddh", "FFC000000" }, \
|
"VISP", "QQIffffffb", "TimeUS,RemTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw,ResetCnt", "sssmmmddh-", "FFC000000-" }, \
|
||||||
{ 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