Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rover: Log_Write_Nav_Tuning should log wp_bearing and nav_bearing in degrees #13162

Merged
merged 1 commit into from Mar 2, 2020

Conversation

rishabsingh3003
Copy link
Contributor

This is in response to #11312.

Copy link
Contributor

@magicrub magicrub left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

wrap_360_cd() needs to change to wrap_360()

@magicrub
Copy link
Contributor

magicrub commented Jan 3, 2020

on a side note for another PR, I see that the wrap_360() and wrap_360_cd() functions start off with a mod function which is relatively expensive. We call those helper functions a lot so we could benefit from an optimization there. We should change that to check for being within 0 to 360 (or 0 to 36000) and exit immediately if within correct bounds.

@rishabsingh3003
Copy link
Contributor Author

wrap_360_cd() needs to change to wrap_360()

That was an embarrassing mistake! Sorry, it's done now!

@magicrub
Copy link
Contributor

magicrub commented Jan 3, 2020

Doesn't this need to be changed for all vehicles? We don't want copter logs having different data than rover/plane/sub

@magicrub
Copy link
Contributor

magicrub commented Jan 3, 2020

ahh, nevermind. I see copter doesn't have it and plane is already fixed. So this fixes it all up. Looks good!

@magicrub
Copy link
Contributor

magicrub commented Jan 3, 2020

well, now that I think of it, this introduces other problems. The units and multipliers are wrong.

Check LogStructure.h

Both plane and Rover have units and multiplier as:

{ 'd', "deg" },           // of the angular variety, -180 to 180
{ 'B', 1e-2 },

Plane log definition:

    { LOG_NTUN_MSG, sizeof(log_Nav_Tuning),         
      "NTUN", "QfcccfffLLii",  "TimeUS,Dist,TBrg,NavBrg,AltErr,XT,XTi,AspdE,TLat,TLng,TAlt,TAspd", "smddmmmnDUmn", "F0BBB0B0GGBB" },

Rover log definition:

    { LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
      "NTUN", "QfHHHf", "TimeUS,WpDist,WpBrg,DesYaw,Yaw,XTrack", "smdddm", "F0BBB0" },

So, if we are wanting 0-360 heading, we'll want unit='h' multiplier='0'. is that what we want? For something like this where two vehicles share a log entry it would be nice to at least have them match (and be correct).

@rishabsingh3003
Copy link
Contributor Author

@magicrub I changed the unit and multiplier for the rover. Hopefully, this is okay now?

@peterbarker
Copy link
Contributor

on a side note for another PR, I see that the wrap_360() and wrap_360_cd() functions start off with a mod function which is relatively expensive. We call those helper functions a lot so we could benefit from an optimization there. We should change that to check for being within 0 to 360 (or 0 to 36000) and exit immediately if within correct bounds.

Good call.

@peterbarker
Copy link
Contributor

on a side note for another PR, I see that the wrap_360() and wrap_360_cd() functions start off with a mod function which is relatively expensive. We call those helper functions a lot so we could benefit from an optimization there. We should change that to check for being within 0 to 360 (or 0 to 36000) and exit immediately if within correct bounds.

Good call.

... actually, I just measured. fly.ArduPlane.MainFlight only calls wrap_360 2,500 times - so it might not be worth it. More measurement would be required to see if it is.

@@ -99,8 +99,8 @@ struct PACKED log_Nav_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
float wp_distance;
uint16_t wp_bearing_cd;
uint16_t nav_bearing_cd;
uint16_t wp_bearing;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please make this float.

@@ -112,8 +112,8 @@ void Rover::Log_Write_Nav_Tuning()
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
time_us : AP_HAL::micros64(),
wp_distance : control_mode->get_distance_to_destination(),
wp_bearing_cd : (uint16_t)wrap_360_cd(control_mode->wp_bearing() * 100),
nav_bearing_cd : (uint16_t)wrap_360_cd(control_mode->nav_bearing() * 100),
wp_bearing : (uint16_t)wrap_360(control_mode->wp_bearing()),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove the cast and the wrap_360

@@ -252,7 +252,7 @@ const LogStructure Rover::log_structure[] = {
{ LOG_THR_MSG, sizeof(log_Throttle),
"THR", "Qhffff", "TimeUS,ThrIn,ThrOut,DesSpeed,Speed,AccY", "s--nno", "F--000" },
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "QfHHHf", "TimeUS,WpDist,WpBrg,DesYaw,Yaw,XTrack", "smdddm", "F0BBB0" },
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Need ot say "float" here.

@rishabsingh3003
Copy link
Contributor Author

@peterbarker done! Please check and let me know if anything else is required This is my first time dealing with logs and was a bit confusing. But it makes perfect sense now :)

@@ -112,8 +112,8 @@ void Rover::Log_Write_Nav_Tuning()
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
time_us : AP_HAL::micros64(),
wp_distance : control_mode->get_distance_to_destination(),
wp_bearing_cd : (uint16_t)wrap_360_cd(control_mode->wp_bearing() * 100),
nav_bearing_cd : (uint16_t)wrap_360_cd(control_mode->nav_bearing() * 100),
wp_bearing : wrap_360(control_mode->wp_bearing()),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't need the wrap_360 here. If it's not between 0 and 360 we have a problem :-)

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe this now does what Randy requested.

@rmackay9 rmackay9 merged commit 0d5f511 into ArduPilot:master Mar 2, 2020
@rmackay9
Copy link
Contributor

rmackay9 commented Mar 2, 2020

I gave this a quick test and it's looking good, thanks very much and sorry for the delay in merging.

@rishabsingh3003
Copy link
Contributor Author

@rmackay9 Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants