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

Copter: Separate max ascent and descent speeds #6951

Merged
merged 1 commit into from
Nov 9, 2017

Conversation

ChrisBird
Copy link
Contributor

In reference to issue #6879

This is for the Copter components only, other pull requests will be generated for Sub and hopefully Plane (quadplane). Change should stand on its own (no library changes, etc)

Note that I've used parameter names that people seemed okay those replying in the issue, if they need changing let me know.

Tested on SITL.

Apologies on the commits (only the last commit is relevant to the copter change but I couldn't get rid of the others - a file got reverted to an old version and committed by accident. I've reverted it back - let me know if I need to fix this up more than I've done to get the pull request through) - still learning git and learning how to fix my mistakes. Only files updated and changed are the Copter files so I think I've managed to fix my mistake.

@Pedals2Paddles
Copy link
Contributor

Nice job! I would backup the files you need and do a git reset on your branch. And then rebase to master. Then add your files again and do the commit. Then force push the branch which will update this PR. That will fix the mess of commits. The pile of merges and reverts may actually make Francisco throw up on his keyboard, and the won't be accepted as it is.

Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

@ChrisBird Regarding git, you want to learn about interactive rebase. Try this command: git rebase -i master, then on the window that will show up with all these commits, you replace the pick with drop (or just d) for the commits you don't want. Using a Git GUI is useful to see the commit history.

Regarding the PR, looks OK to me, except the numbers used and we need to do a conversion from the old value to the new ones if the user has any value saved. We can certainly help with that.

// Pilot_Velocity Extras - 260
//
k_param_pilot_velocity_z_max_up = 260,
k_param_pilot_velocity_z_max_dn = 261,
Copy link
Member

Choose a reason for hiding this comment

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

This needs to be verified, but I think we can't use these numbers, that's why we already have another group of parameters.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Hi @OXINARF, I must be misunderstanding something? I'm still learning the codebase (and my c++ skills are a little rusty) so apologies if I'm making basic mistakes. I gave the new ones a new block and gave them values not in the enum list?

Thanks for the above git suggestions, I'll give it a go when I get home.

@rmackay9
Copy link
Contributor

In general looking pretty good.

We should continue to use the old enum location even though we are renaming the parameter to "PILOT_SPEED_UP" or everyone will lose whatever their current value is (although many do not change it).

I think we should do one of these two things:

@ChrisBird
Copy link
Contributor Author

I'll make some changes tonight (fixing up my commits) and I'll add @rmackay9 2nd suggestion as it would be cleaner. I knew it could do the conversion but never knew how, looks straight forwards.

@ChrisBird ChrisBird force-pushed the 6879_fixed branch 3 times, most recently from 214091d to 2a5a477 Compare September 15, 2017 13:10
@ChrisBird
Copy link
Contributor Author

ChrisBird commented Sep 15, 2017

@rmackay9 @OXINARF I've updated it as per the recommendations above. Since the parameter for dn was on it own now, I moved it to 256 just passed the reserved values.

I think I even managed to get it to fit into the one commit too, starting to understand how git works now (anyone know a good svn to git primer - none i've seen seem to click for me for some reason).

Let me know if anything else needs changing.

Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

@ChrisBird I'm sorry you were induced in error, but the current code doesn't work. The conversion works when an old parameter is removed and a new one added, which isn't the case now - with this code, if the user changed PILOT_SPEED_UP and had never changed PILOT_SPEED_DOWN, then it would also be changed in the next reboot without the user being aware.
So, like @rmackay9 said, we either:

  • make two new parameters and convert old one into these two new ones, or
  • leave the existing parameter and make a new one that defaults to 0, in which case the old parameter should be used

Like I said before, I think we can't use any enum value above 255. We have another space of parameters and a comment there says exactly this: https://github.com/ArduPilot/ardupilot/blob/master/ArduCopter/Parameters.h#L505
So we should add the new parameter in G2. If you need help with that, we are available to help in Gitter.

@ChrisBird
Copy link
Contributor Author

Ah i see what you mean now. I'll update it to use the other block. I'll do the first option. I'll get an update out today.

@ChrisBird ChrisBird force-pushed the 6879_fixed branch 3 times, most recently from 8e25730 to cc2c92b Compare September 16, 2017 02:39
@ChrisBird
Copy link
Contributor Author

@OXINARF, I think I've resolved all the issues identified. Given we've run out of room in the top level params it might be worthwhile updating the How to on the dev page. If I get a chance I'll give updating the doco a go - seems its more like what we have in the adding a param to a library.

Reason I initially did it is due to this comment and the how to add a new param page:
// the k_param_* space is 9-bits in size
// 511: reserved

I assumed I was good to use all 9 bits, I did think it was odd at the time and didn't fully understand the earlier parameter comment you made, the 2nd one made sense to me and hopefully I've done it correctly. Seems to work on my SITL tests.

Maybe we should change that first line to:
// the k_param_* space is 9-bits in size. However only 8 bits is accessible

Anyway, I've updated the code so it should be using G2 parameters instead and I believe I've fixed the conversion issue you raised.

I'll get there its only my 2nd PR, still learning. Thanks for your help!

Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

LGTM. The commit message should be changed before merge, but we can do that - tip: either use fixup on Git interactive rebase or when squashing edit the commit message in the end, otherwise it can end up being messy like the one here.

@rmackay9 Do you approve?

@ChrisBird
Copy link
Contributor Author

Hi @rmackay9, let me know if it needs any further work?

@OXINARF
Copy link
Member

OXINARF commented Oct 18, 2017

@ChrisBird Unfortunately I was late to the dev call where this was discussed so I'm not completely sure what @rmackay9 said there, but from reading the minutes of the meeting, it looks like he wants to have the other option implemented instead (keep the same parameter and add a new one with default value of 0, which means use existing parameter).

@ChrisBird
Copy link
Contributor Author

@OXINARF I'll make the change over the weekend.

@ChrisBird
Copy link
Contributor Author

Hi @OXINARF, I think I've done something wrong on the rebase to get all the commits above there. I've put a request out on Gitter to seek help but if now one gets back to me can you advise what I should do?

Should I be using the fixup option? Or is some other course of action recommended. Apologies for this, it seems Git is still kicking my butt. I'll get it eventually.....

Also I'm confused why the conflict messages, as I resolved the conflicts on my end (winch was using the same parameter number as me orginally), so I'm not sure why they have appeared here.

@OXINARF
Copy link
Member

OXINARF commented Oct 29, 2017

@ChrisBird Waiting for you in Gitter 🙂 No, don't use fixup, you need to rebase.

@ChrisBird
Copy link
Contributor Author

@rmackay9 Can you let me know if the changes I've made are in line with what was discussed on the dev call? I've only got the minutes to work off and I'd like to get this one finalised. The issue I mentioned above, @OXINARF was able to help me resolve on the day.

Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

I made a few more comments, nothing major but there is a bug.

@@ -307,3 +307,12 @@ void Copter::rotate_body_frame_to_NE(float &x, float &y)
x = ne_x;
y = ne_y;
}

// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
uint16_t Copter::get_pilot_z_max_dn_velz()
Copy link
Member

Choose a reason for hiding this comment

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

Nitpicking: I think this was better named get_pilot_velocity_z_max_dn.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

It makes sense, I've changed it.

@@ -68,7 +68,7 @@ void Copter::sport_run()

// get pilot desired climb rate
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
target_climb_rate = constrain_float(target_climb_rate, -g2.pilot_velocity_z_max_dn, g.pilot_velocity_z_max_up);
Copy link
Member

Choose a reason for hiding this comment

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

It's not calling the method.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Hmmm, annoyed at myself on this one. I've fixed it up in the latest commit.

# define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s
#endif
#ifndef PILOT_ACCEL_Z_DEFAULT
# define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control
#endif
#ifndef PILOT_SPEED_DEF
# define PILOT_SPEED_DEF 250 // maximum vertical velocity in cm/s
#endif
Copy link
Member

Choose a reason for hiding this comment

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

I think we don't need to change the macro name, but if you want to do that, change the old macro name, don't add a new one and leave the old, unused, one.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I've reverted to using the old name, removed the PILOT_SPEED_DEF and removed the comment deprecating the original name.

// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
uint16_t Copter::get_pilot_z_max_dn_velz()
{
if(g2.pilot_velocity_z_max_dn == 0)
Copy link
Member

Choose a reason for hiding this comment

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

Style rules: space after if and you need braces

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Updated in latest commit

if(g2.pilot_velocity_z_max_dn == 0)
return g.pilot_velocity_z_max_up;
else
return g2.pilot_velocity_z_max_dn;
Copy link
Member

Choose a reason for hiding this comment

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

It would probably be a good idea to put an abs around this to prevent anyone inserting a negative value.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Agreed, updated in latest commit

Added equivalent parameters to WPNAV_SPEED_UP and WPNAV_SPEED_DN

New parameters named:
PILOT_SPEED_UP (technically renamed PILOT_VELZ_MAX)
PILOT_SPEED_DN

Removed parameter PILOT_VELZ_MAX (technically renamed to PILOT_SPEED_UP).

Flight Modes impacted:
ALTHOLD
AUTOTUNE
CIRCLE
LOITER
POSHOLD
SPORT
TAKEOFF

Update a section in GUIDED mode but I don't think it is ever used but update just in case.

It will use the PILOT_SPEED_UP for ascending max velocity.  For down it will check if
it is 0, if so then it will PILOT_SPEED_UP instead, if non zero it will use PILOT_SPEED_DN.
This retains current behavior and gives the flexibility to change it if desired.
@ChrisBird
Copy link
Contributor Author

@rmackay9 I decided to do the changes now. They are done however it looks like the travis ci sitltest failed (in rover code, looks like others have had the same issue from what I could see), so once that is fixed it should pass the sitltest.

@Pedals2Paddles
Copy link
Contributor

Looks like all checks have passed now.

@rmackay9 rmackay9 merged commit caaeae3 into ArduPilot:master Nov 9, 2017
@rmackay9
Copy link
Contributor

rmackay9 commented Nov 9, 2017

Merged, thanks!

@ChrisBird ChrisBird deleted the 6879_fixed branch November 10, 2017 11:01
@Pedals2Paddles
Copy link
Contributor

I used this today and it was magical! Little things like this make a big difference when this little thing has been an annoyance for years.

I set a max descent rate that will be smooth, just on the edge of where it starts to wobble in it's own wake turbulence. This made the video I was shooting today so much easier to manage and has an immediate effect on quality. I no longer need to micro manage my descent rate and I can focus on the shot I'm trying to get.

Thank you!

@ChrisBird
Copy link
Contributor Author

No probs, glad you've been able to test it out. It'll be a few weeks before i can fly it on a real multi. I'll be going through the issues list and working on some of the older simple items to help me learn the code.

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

Successfully merging this pull request may close these issues.

None yet

4 participants