-
Notifications
You must be signed in to change notification settings - Fork 13.5k
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
0 bank angle for GPS failure on landing #13795
base: main
Are you sure you want to change the base?
Conversation
…hicle is on slope for landing and enters a gps failure mode, the vehicle will continue straight ahead with wings level. Otherwise it behaves normally.
src/modules/navigator/gpsfailure.cpp
Outdated
//This determines if the fixedwing vehicle is landing or not, and if so it forces the wings level | ||
//Otherwise the plane goes to the parameter set fixed bank loiter setting | ||
|
||
if (stat->nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Checking the nav_state is redundant. https://github.com/PX4/Firmware/blob/89e1f478ac9f3863df4f5613cf111222ae9c7749/src/modules/navigator/navigator_main.cpp#L617
src/modules/navigator/gpsfailure.cpp
Outdated
|
||
if (stat->nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL | ||
&& pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LAND) { | ||
att_sp.roll_body = 0; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
att_sp.roll_body = 0; | |
att_sp.roll_body = 0.0f; |
src/modules/navigator/gpsfailure.cpp
Outdated
//Otherwise the plane goes to the parameter set fixed bank loiter setting | ||
|
||
if (stat->nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL | ||
&& pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LAND) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
To be paranoid, also check that it's valid
&& pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LAND) { | |
&& pos_sp_triplet->current.t.valid && (pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LAND)) { |
Adding the way-point validity check to this breaks it currently. When it enters the fail safe mode, the current waypoint becomes invalid leading to it still using the fixed-bank loiter setting. |
Here is a log with the waypoint validity check: https://review.px4.io/plot_app?log=9f8842c3-bec7-4984-a6d8-03611e6d47a5 And here is a log without it: https://review.px4.io/plot_app?log=505571cc-7a93-4201-9367-80aa66963dcc |
Ok we'll need to think of something else then. What if you do the check in |
Could we use Navigator::on_mission_landing() in the GpsFailure::on_activation() to store the was landing flag? And would we want to do it in the GpsFailure::on_inactive() rather than on_activation() so that we don't run into any invalid issues with the gps failure activating? EDIT |
src/modules/navigator/gpsfailure.cpp
Outdated
} else { | ||
att_sp.roll_body = math::radians(_param_nav_gpsf_r.get()); | ||
} | ||
|
||
att_sp.pitch_body = math::radians(_param_nav_gpsf_p.get()); | ||
att_sp.thrust_body[0] = _param_nav_gpsf_tr.get(); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Does it still make sense to use the same gps failsafe throttle? This might result in a fly away if misconfigured
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Good point! Should we also force throttle to 0 if already landing?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
After thinking about it more I think we should also force throttle to 0. If the vehicle was already landing, the intent is to get on the ground. In this case the best course of action is to continue wings level and cut throttle to ensure the vehicle gets on the ground. @Kjkinney can you add this code and code comments explaining why?
I added the changes above. Here is a SITL test log https://review.px4.io/plot_app?log=aff020ae-2efd-49ad-a207-30879d642283 |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I agree with the functional change but not with the implementation.
You are essentially changing the state called GPSF_STATE_LOITER
, however, the more appropriate way to implement this would be to add a state, e.g. GPSF_STATE_LAND
.
This has the benefit that you can announce the action correctly in on_activation()
. Right now, it will display "Global position failure: fixed bank loiter" even though it is about to land which can be confusing for the operator.
I would therefore add a state and then check in advance_gpsf()
which state you should go to depending on the was_landing
flag. Then you can implement the correct setpoint in the respective state in on_active()
.
Do you think that would make sense?
I agree that it would make more sense to split the two cases. |
This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions. |
Describe problem solved by this pull request
On landing currently if an airplane enters a gps failure state, the plane will enter a fixed bank loiter, beginning a circle while on the landing path. What this does is allows the plane to instead keep the wings level in a failure instead of spiraling away from the land point.
Describe your solution
This commit checks if the plane is landing or not, and in a failure state. If so the navigator publishes a 0 bank angle in order to keep the plane heading towards the land point. Otherwise fixed bank loiter behaves exactly the same.
Describe possible alternatives
I used an alternate way of determining if the plane was landing within navigator_main. This version moves everything into gpsfailure. There might be a redundant boolean within the if statement currently.
Test data / coverage
This was tested in SITL in multiple different stages of flight to confirm nothing was broken when creating this.
https://review.px4.io/plot_app?log=683a837c-86d6-4d17-9330-2a47a87cc89f
Additional context
We have been flying with a different version of this on our own Fixed Wings for 6 months
@Antiheavy