AP_Logger: Update logs based on new BendyRuler type
This commit is contained in:
parent
b62455fd3f
commit
ad3a7e4d49
@ -285,7 +285,7 @@ public:
|
|||||||
void Write_Beacon(AP_Beacon &beacon);
|
void Write_Beacon(AP_Beacon &beacon);
|
||||||
void Write_Proximity(AP_Proximity &proximity);
|
void Write_Proximity(AP_Proximity &proximity);
|
||||||
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
|
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
|
||||||
void Write_OABendyRuler(bool active, float target_yaw, bool ignore_chg, float margin, const Location &final_dest, const Location &oa_dest);
|
void Write_OABendyRuler(uint8_t type, bool active, float target_yaw, float target_pitch, bool ignore_chg, float margin, const Location &final_dest, const Location &oa_dest);
|
||||||
void Write_OADijkstra(uint8_t state, uint8_t error_id, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
|
void Write_OADijkstra(uint8_t state, uint8_t error_id, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
|
||||||
void Write_SimpleAvoidance(uint8_t state, const Vector2f& desired_vel, const Vector2f& modified_vel, bool back_up);
|
void Write_SimpleAvoidance(uint8_t state, const Vector2f& desired_vel, const Vector2f& modified_vel, bool back_up);
|
||||||
void Write_Winch(bool healthy, bool thread_end, bool moving, bool clutch, uint8_t mode, float desired_length, float length, float desired_rate, uint16_t tension, float voltage, int8_t temp);
|
void Write_Winch(bool healthy, bool thread_end, bool moving, bool clutch, uint8_t mode, float desired_length, float length, float desired_rate, uint16_t tension, float voltage, int8_t temp);
|
||||||
|
@ -1044,20 +1044,24 @@ void AP_Logger::Write_SRTL(bool active, uint16_t num_points, uint16_t max_points
|
|||||||
WriteBlock(&pkt_srtl, sizeof(pkt_srtl));
|
WriteBlock(&pkt_srtl, sizeof(pkt_srtl));
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Logger::Write_OABendyRuler(bool active, float target_yaw, bool resist_chg, float margin, const Location &final_dest, const Location &oa_dest)
|
void AP_Logger::Write_OABendyRuler(uint8_t type, bool active, float target_yaw, float target_pitch, bool resist_chg, float margin, const Location &final_dest, const Location &oa_dest)
|
||||||
{
|
{
|
||||||
const struct log_OABendyRuler pkt{
|
const struct log_OABendyRuler pkt{
|
||||||
LOG_PACKET_HEADER_INIT(LOG_OA_BENDYRULER_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_OA_BENDYRULER_MSG),
|
||||||
time_us : AP_HAL::micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
|
type : type,
|
||||||
active : active,
|
active : active,
|
||||||
target_yaw : (uint16_t)wrap_360(target_yaw),
|
target_yaw : (uint16_t)wrap_360(target_yaw),
|
||||||
yaw : (uint16_t)wrap_360(AP::ahrs().yaw_sensor * 0.01f),
|
yaw : (uint16_t)wrap_360(AP::ahrs().yaw_sensor * 0.01f),
|
||||||
|
target_pitch: (uint16_t)target_pitch,
|
||||||
resist_chg : resist_chg,
|
resist_chg : resist_chg,
|
||||||
margin : margin,
|
margin : margin,
|
||||||
final_lat : final_dest.lat,
|
final_lat : final_dest.lat,
|
||||||
final_lng : final_dest.lng,
|
final_lng : final_dest.lng,
|
||||||
|
final_alt : final_dest.alt,
|
||||||
oa_lat : oa_dest.lat,
|
oa_lat : oa_dest.lat,
|
||||||
oa_lng : oa_dest.lng
|
oa_lng : oa_dest.lng,
|
||||||
|
oa_alt : oa_dest.alt
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
@ -1170,15 +1170,19 @@ struct PACKED log_SRTL {
|
|||||||
struct PACKED log_OABendyRuler {
|
struct PACKED log_OABendyRuler {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
|
uint8_t type;
|
||||||
uint8_t active;
|
uint8_t active;
|
||||||
uint16_t target_yaw;
|
uint16_t target_yaw;
|
||||||
uint16_t yaw;
|
uint16_t yaw;
|
||||||
|
uint16_t target_pitch;
|
||||||
bool resist_chg;
|
bool resist_chg;
|
||||||
float margin;
|
float margin;
|
||||||
int32_t final_lat;
|
int32_t final_lat;
|
||||||
int32_t final_lng;
|
int32_t final_lng;
|
||||||
|
int32_t final_alt;
|
||||||
int32_t oa_lat;
|
int32_t oa_lat;
|
||||||
int32_t oa_lng;
|
int32_t oa_lng;
|
||||||
|
int32_t oa_alt;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_OADijkstra {
|
struct PACKED log_OADijkstra {
|
||||||
@ -1910,15 +1914,19 @@ struct PACKED log_Winch {
|
|||||||
// @LoggerMessage: OABR
|
// @LoggerMessage: OABR
|
||||||
// @Description: Object avoidance (Bendy Ruler) diagnostics
|
// @Description: Object avoidance (Bendy Ruler) diagnostics
|
||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
// @Field: Active: True if Bendy Ruler avoidance is being used
|
// @Field: Type: Type of BendyRuler currently active
|
||||||
// @Field: DesYaw: Best yaw chosen to avoid obstacle
|
// @Field: Act: True if Bendy Ruler avoidance is being used
|
||||||
|
// @Field: DYaw: Best yaw chosen to avoid obstacle
|
||||||
// @Field: Yaw: Current vehicle yaw
|
// @Field: Yaw: Current vehicle yaw
|
||||||
// @Field: ResChg: True if BendyRuler resisted changing bearing and continued in last calculated bearing
|
// @Field: DP: Desired pitch chosen to avoid obstacle
|
||||||
|
// @Field: RChg: True if BendyRuler resisted changing bearing and continued in last calculated bearing
|
||||||
// @Field: Mar: Margin from path to obstacle on best yaw chosen
|
// @Field: Mar: Margin from path to obstacle on best yaw chosen
|
||||||
// @Field: DLat: Destination latitude
|
// @Field: DLt: Destination latitude
|
||||||
// @Field: DLng: Destination longitude
|
// @Field: DLg: Destination longitude
|
||||||
// @Field: OALat: Intermediate location chosen for avoidance
|
// @Field: DAlt: Desired alt
|
||||||
// @Field: OALng: Intermediate location chosen for avoidance
|
// @Field: OLt: Intermediate location chosen for avoidance
|
||||||
|
// @Field: OLg: Intermediate location chosen for avoidance
|
||||||
|
// @Field: OAlt: Intermediate alt chosen for avoidance
|
||||||
|
|
||||||
// @LoggerMessage: OADJ
|
// @LoggerMessage: OADJ
|
||||||
// @Description: Object avoidance (Dijkstra) diagnostics
|
// @Description: Object avoidance (Dijkstra) diagnostics
|
||||||
@ -2485,7 +2493,7 @@ struct PACKED log_Winch {
|
|||||||
{ LOG_SRTL_MSG, sizeof(log_SRTL), \
|
{ LOG_SRTL_MSG, sizeof(log_SRTL), \
|
||||||
"SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \
|
"SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \
|
||||||
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
|
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
|
||||||
"OABR","QBHHBfLLLL","TimeUS,Active,DesYaw,Yaw,ResChg,Mar,DLat,DLng,OALat,OALng", "sbdd-mDUDU", "F-----GGGG" }, \
|
"OABR","QBBHHHBfLLfLLf","TimeUS,Type,Act,DYaw,Yaw,DP,RChg,Mar,DLt,DLg,DAlt,OLt,OLg,OAlt", "s-bddd-mDUmDUm", "F-------GGBGGB" }, \
|
||||||
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
|
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
|
||||||
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" }, \
|
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" }, \
|
||||||
{ LOG_SIMPLE_AVOID_MSG, sizeof(log_SimpleAvoid), \
|
{ LOG_SIMPLE_AVOID_MSG, sizeof(log_SimpleAvoid), \
|
||||||
|
Loading…
Reference in New Issue
Block a user