AP_Logger: Log if BendyRuler has avoided changing directions

This commit is contained in:
Rishabh 2020-06-21 18:55:41 +05:30 committed by Randy Mackay
parent 7dd7565d14
commit 4fa2c3f5ba
3 changed files with 6 additions and 3 deletions

View File

@ -287,7 +287,7 @@ public:
void Write_Beacon(AP_Beacon &beacon);
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_OABendyRuler(bool active, float target_yaw, float margin, const Location &final_dest, const Location &oa_dest);
void Write_OABendyRuler(bool active, float target_yaw, 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(const char *name, const char *labels, const char *fmt, ...);

View File

@ -1042,7 +1042,7 @@ void AP_Logger::Write_SRTL(bool active, uint16_t num_points, uint16_t max_points
WriteBlock(&pkt_srtl, sizeof(pkt_srtl));
}
void AP_Logger::Write_OABendyRuler(bool active, float target_yaw, float margin, const Location &final_dest, const Location &oa_dest)
void AP_Logger::Write_OABendyRuler(bool active, float target_yaw, bool resist_chg, float margin, const Location &final_dest, const Location &oa_dest)
{
const struct log_OABendyRuler pkt{
LOG_PACKET_HEADER_INIT(LOG_OA_BENDYRULER_MSG),
@ -1050,6 +1050,7 @@ void AP_Logger::Write_OABendyRuler(bool active, float target_yaw, float margin,
active : active,
target_yaw : (uint16_t)wrap_360(target_yaw),
yaw : (uint16_t)wrap_360(AP::ahrs().yaw_sensor * 0.01f),
resist_chg : resist_chg,
margin : margin,
final_lat : final_dest.lat,
final_lng : final_dest.lng,

View File

@ -1171,6 +1171,7 @@ struct PACKED log_OABendyRuler {
uint8_t active;
uint16_t target_yaw;
uint16_t yaw;
bool resist_chg;
float margin;
int32_t final_lat;
int32_t final_lng;
@ -1844,6 +1845,7 @@ struct PACKED log_Arm_Disarm {
// @Field: Active: True if Bendy Ruler avoidance is being used
// @Field: DesYaw: Best yaw chosen to avoid obstacle
// @Field: Yaw: Current vehicle yaw
// @Field: ResChg: True if BendyRuler resisted changing bearing and continued in last calculated bearing
// @Field: Mar: Margin from path to obstacle on best yaw chosen
// @Field: DLat: Destination latitude
// @Field: DLng: Destination longitude
@ -2388,7 +2390,7 @@ struct PACKED log_Arm_Disarm {
{ LOG_SRTL_MSG, sizeof(log_SRTL), \
"SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
"OABR","QBHHfLLLL","TimeUS,Active,DesYaw,Yaw,Mar,DLat,DLng,OALat,OALng", "sbddmDUDU", "F----GGGG" }, \
"OABR","QBHHBfLLLL","TimeUS,Active,DesYaw,Yaw,ResChg,Mar,DLat,DLng,OALat,OALng", "sbdd-mDUDU", "F-----GGGG" }, \
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" }, \
{ LOG_IMU2_MSG, sizeof(log_IMU), \