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

Adjustable land speed via RC #12220

Merged
merged 9 commits into from
Jul 9, 2019
Merged

Adjustable land speed via RC #12220

merged 9 commits into from
Jul 9, 2019

Conversation

dakejahl
Copy link
Contributor

@dakejahl dakejahl commented Jun 9, 2019

Describe problem solved by the proposed pull request
This allows user input to assist in a quicker land during the land routine. This is enabled by a parameter which defaults to disabled.

  • Enable user assisted descent speed for autonomous land routine.
  • When enabled, descent speed will be equal to MPC_LAND_SPEED at half throttle,
  • MPC_Z_VEL_MAX_DN at zero throttle, and 0.5 m/s at full throttle.

Test data / coverage
Tested in sim using a Taranis X7 plugged in via USB (QGC Joystick)
https://review.px4.io/plot_app?log=b3208c83-0f28-4a43-ba85-0324b4f785be

Additional context
This is a feature DJI has and I have found it to be extremely convenient. Users switching from DJI to PX4 builds are not going to like losing features 😉

Edit: it would also be cool to be able to adjust the X/Y position during land. If anyone else thinks this is worth adding I can do that as well.

@dakejahl dakejahl force-pushed the pr-assisted_land_speed branch 2 times, most recently from b6c6b1d to efc2617 Compare June 9, 2019 08:47
@dakejahl
Copy link
Contributor Author

dakejahl commented Jun 9, 2019

We might want a check for _sub_manual_control_setpoint->get().source == SOURCE_RC. What do you think @dagar?

@dakejahl dakejahl requested a review from MaEtUgR June 9, 2019 19:00
@dakejahl dakejahl requested a review from dagar June 9, 2019 19:00
@dakejahl
Copy link
Contributor Author

dakejahl commented Jun 11, 2019

Also it might be nice to make this a parameter that defaults to DISABLED, as people will probably have the throttle stick down while landing, and the increased descent speed would be very concerning if they were not aware of the fact that their stick positions are now contributing to the descent speed.

@dakejahl
Copy link
Contributor Author

@LorenzMeier Do you have any comments/concerns? Do you think this is a feature worth pursuing?

@dagar
Copy link
Member

dagar commented Jun 11, 2019

This has come up before and high level I think it's a good idea, but we need to be extremely careful with the user interaction as well as failsafe edge cases (intermittent manual control with the stick in a weird position).

At a minimum I'd update it to respect the systems notion of manual control lost (vehicle_status.rc_signal_lost) and put it behind a parameter that's disabled by default (at least to start).

@dagar
Copy link
Member

dagar commented Jun 11, 2019

We might want a check for _sub_manual_control_setpoint->get().source == SOURCE_RC. What do you think @dagar?

Why treat RC differently than mavlink?

@dakejahl
Copy link
Contributor Author

We might want a check for _sub_manual_control_setpoint->get().source == SOURCE_RC. What do you think @dagar?

Why treat RC differently than mavlink?

Yeah, that was my first thought. Nvm then.

@dakejahl
Copy link
Contributor Author

At a minimum I'd update it to respect the systems notion of manual control lost (vehicle_status.rc_signal_lost) and put it behind a parameter that's disabled by default (at least to start).

rgr rgr

@dakejahl
Copy link
Contributor Author

dakejahl commented Jun 12, 2019

This is complete. Ready for final review. If you look at flight log from sim, I turned on/off the parameter as well as unplugged/replugged the RC. I probably won't make it to the dev call tomorrow.

dakejahl and others added 4 commits June 15, 2019 19:23
…. Added a _getLandSpeed function the the FlightTaskAutoMapper2 class which uses the manual_control_setpoint topic to adjust landing descent speed based on user input
Co-Authored-By: Daniel Agar <[email protected]>
…status.rc_signal_lost. Added a parameter for this feature that defaults to disabled.
@bresch
Copy link
Member

bresch commented Jul 3, 2019

@PX4/testflights Can you test this PR in mission mode and set MPC_LAND_RC_HELP to 1.
During landing, try to move the throttle stick in order to modify the landing speed.

@Junkim3DR
Copy link

Junkim3DR commented Jul 3, 2019

@bresch @dagar, the feature is not working at the moment.

Tested on Pixhawk 4 mini v5

Procedure

  • Changed parameter MPC_LAND_RC_HELP form 0 to 1
  • Arm and Take off in position mode, after flying for approximately one minute, trigger RTL, wait for vehicle to return, while landing test throttle stick up, middle and down, see vehicle behavior.

Notes
Vehicle landed as usual, we moved the throttle stick up then left it there for about 5 seconds, continued to middle position and left it there 5 seconds as well, same procedure for down position; vehicle kept its landing velocity and no change was noticed.

Log
https://review.px4.io/plot_app?log=396e2f3a-b372-47de-b63c-50dfeeac9692

Tested on Pixhawk Pro v4 and Pixhawk 4 v5 and same results.

@bresch
Copy link
Member

bresch commented Jul 3, 2019

@Junkim3DR , thanks for the tests. I checked the logs and it is actually working. The problem why you didn't see it is that this logic is only active in "land mode". During RTL, the drone is in land mode during the last 10 meters (RTL_DESCEND_ALT) only. Furthermore, since the maximum down speed is 1 (MPC_Z_VEL_MAX_DN) during full stick down, the land speed is 0.7 (MPC_LAND_SPEED) when stick centered and the lower speed is 0.5 (hardcoded in this PR) when stick up, the difference is not that visible.
It will be more noticeable if you increase MPC_Z_VEL_MAX_DOWN to at something like 2m/s.

Here is the plot showing that it worked in your test:
2019-07-03_21-54-34_01_plot

This is unfortunately the tiny last part of the flight (because it's only active during the last 10 meters):
2019-07-03_22-23-11_01_plot

bresch
bresch previously approved these changes Jul 3, 2019
Copy link
Member

@bresch bresch left a comment

Choose a reason for hiding this comment

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

Thanks for that nice feature!
The XY adjustments would also be something super nice. Currently we have to switch to manual position mode and is not as nice as being able to adjust the landing while in auto mode.

@dakejahl
Copy link
Contributor Author

dakejahl commented Jul 3, 2019

the lower speed is 0.5 (hardcoded in this PR) when stick up

Actually I think my comment in the parameter file is wrong, looks like I changed it to

		// Allow minimum assisted land speed to be half of parameter
		if (speed < land_speed * 0.5f) {
			speed = land_speed * 0.5f;
		}

What do you think is best? A fixed small value like 0.5? A number that is a function of the land speed like the current implementation? Maybe another parameter to set this?

I'll see what I can do for XY control, look for a PR soon.

@bresch
Copy link
Member

bresch commented Jul 4, 2019

Right, I think 0.5 x land speed is a reasonable choice. Can you update the parameter description please?

@dakejahl
Copy link
Contributor Author

dakejahl commented Jul 4, 2019

Done

Copy link
Member

@bresch bresch left a comment

Choose a reason for hiding this comment

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

All good now

@dagar
Copy link
Member

dagar commented Jul 5, 2019

Slightly over the fmu-v2 flash limit.

image

@dagar dagar merged commit 59c555a into master Jul 9, 2019
@dagar dagar deleted the pr-assisted_land_speed branch July 9, 2019 03:55
float land_speed = _param_mpc_land_speed.get();
float head_room = _constraints.speed_down - land_speed;

speed = land_speed + 2 * (0.5f - throttle) * head_room;
Copy link
Member

Choose a reason for hiding this comment

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

I don't want to offend at all but this implementation is quite hacky and needs improvement for sure.
Issues that come to my mind:

Copy link
Contributor Author

Choose a reason for hiding this comment

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

No offense taken at all, I like critical feedback. I am pretty unfamiliar with FlightTasks in general, so indeed it may be hacky as I was unsure the correct spot to put this.

We should support general correction of the land location by sticks not only adjusting the land speed.

I've got a WIP branch open right now. My plan was to move the sticks stuff into the FlightTask base class so I could use _evaluateSticks

It's implemented in AutoMapper2 which duplicates big parts of AutoMapper so in some configurations this feature is not available.

I was very confused by the naming of these two. Without getting intimate with the code, it is very unclear what their roles/responsibilities are. I actually implemented it AutoMapper at first and then realized nothing was happening.

If you've got any suggestions or just random details in general don't hesitate to share. Thanks!

Copy link
Member

@MaEtUgR MaEtUgR Oct 21, 2019

Choose a reason for hiding this comment

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

I've got a WIP branch open right now. My plan was to move the sticks stuff into the FlightTask base class so I could use _evaluateSticks

I'm quite sure by now that inheriting all the data processing in the flight tasks does not scale. We should pull e.g. the stick processing into a library such that not every task that uses sticks has to inherit from Manual. (The same of course also for other reusable logic.)

I was very confused by the naming of these two.

That's definitely far from your fault. They do almost completely the same thing but for later auto task with the "AutoSmoothVel" ending (which is default) there are some small differences. We need to get rid of that duplication, here's the issue for that: #11209. The existence of Automapper and having two versions is in my eyes partly caused by the inheritance structure.

Copy link
Member

@MaEtUgR MaEtUgR Feb 19, 2020

Choose a reason for hiding this comment

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

@dakejahl JFYI the duplicate AutoMapper is gone since 7e78eed 🎉

Copy link
Member

Choose a reason for hiding this comment

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

@dakejahl JFYI the stick handling was moved to a library (#15324) and I have a pr open reusing it for the auto land use case you contributed: #15325

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Sweet! Have others found it useful? Haha I never did get around to allowing XY control, it would be cool if it did

Copy link
Member

@MaEtUgR MaEtUgR Jul 15, 2020

Choose a reason for hiding this comment

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

I think it doesn't get used that often because of RC override which by default makes it switch out of land when you move the sticks. We'll enable x, y control soon. We can still discuss how it should work together with the mode override.
btw I changed the behavior a bit to not have such a high downwards speed on the sticks. Is that a problem? We can maybe discuss in the dev call...

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

Successfully merging this pull request may close these issues.

5 participants