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

Log vehicle local position setpoints for fixedwing position control #18929

Merged
merged 2 commits into from
Jan 3, 2022

Conversation

Jaeyoung-Lim
Copy link
Member

@Jaeyoung-Lim Jaeyoung-Lim commented Dec 31, 2021

Describe problem solved by this pull request
Previously it was hard to interpret what the fw position controller was doing in term of tracking performance since the position setpoints were not logged in the local frame.

  • It is hard to associate waypoints switching with the vehicle behavior, given that the fw pos control overrides the setpoints internally sometimes
  • This is especially a problem when passing high bandwidth setpoints from offboard or for path tracking.
  • For VTOLs the position setpoints just stops logging when the vehicle transitions to FW mode, since the local_position_setpoint is only published from the MC position controller module

Describe your solution
This adds publication of the vehicle_local_position_setpoint so that it gets logged as a local setpoint.

Describe possible alternatives

  • I think a bigger problem creeping is that all our position setpoints are in the global frame due to L1 only supporting lat/lon as a input. For offboard mode, we are converting local->global and global->local two times for this reason. I would like to move towards doing fw control in local coordinates since this would allow us to fly even in GPS denied situations.

Test data / coverage
Tested in SITL Gazebo

make px4_sitl gazebo_plane

and the log correctly shows the position setpoints and how the waypoints are switching.

Additional context

This commit enables the local position setpoints to be logged by publishing vehicle_local_position_setpoint
if (_global_local_proj_ref.isInitialized()) {
Vector2f current_setpoint = _global_local_proj_ref.project(current_waypoint.lat, current_waypoint.lon);
vehicle_local_position_setpoint_s local_position_setpoint{};
local_position_setpoint.x = current_setpoint(0);
Copy link
Member

Choose a reason for hiding this comment

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

populate the unused fields with NANs?

local_position_setpoint.vx = NAN, etc

Copy link
Member

Choose a reason for hiding this comment

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

Alternatively does populating any other existing data make sense (for casual interest)?

  • acceleration from L1?
  • velocities from TECS (remove wind?)

Copy link
Member Author

@Jaeyoung-Lim Jaeyoung-Lim Jan 1, 2022

Choose a reason for hiding this comment

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

I think for now IMO there is not much more to add - e.g. velocity setpoints are not used byt the controller / accelerations are not used by the controller. I think we can add these by cleaning up the controller one by one (e.g. change L1 controller to command accelerations, rather than roll angles)

Copy link
Contributor

Choose a reason for hiding this comment

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

Some stuff - e.g. lateral acceleration- will be published with the new L1 controller (#18810) in npfg_status. I would also find it nicer if we publish whatever we can in local_position_setpoint. That though also requires some controller interface alignment - using local coordinates prob is one thing of that.

@dagar
Copy link
Member

dagar commented Dec 31, 2021

Looks good, although doesn't this need to be skipped during VTOL transitions?

@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Jan 1, 2022

Looks good, although doesn't this need to be skipped during VTOL transitions?

@dagar Done! Happy new year! 🎉

This commit adds disabling vehicle setpoints while in transition
@Jaeyoung-Lim Jaeyoung-Lim force-pushed the pr-fw-local-pos-control branch from 3f892ea to 30a3ca9 Compare January 1, 2022 18:48
Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

Thanks, that makes sense.

Let's figure out if it makes sense to pull some more data out of tecs_status and npfg_status into vehicle_local_position setpoint.

if (_global_local_proj_ref.isInitialized()) {
Vector2f current_setpoint = _global_local_proj_ref.project(current_waypoint.lat, current_waypoint.lon);
vehicle_local_position_setpoint_s local_position_setpoint{};
local_position_setpoint.x = current_setpoint(0);
Copy link
Contributor

Choose a reason for hiding this comment

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

Some stuff - e.g. lateral acceleration- will be published with the new L1 controller (#18810) in npfg_status. I would also find it nicer if we publish whatever we can in local_position_setpoint. That though also requires some controller interface alignment - using local coordinates prob is one thing of that.

@Jaeyoung-Lim
Copy link
Member Author

Some stuff - e.g. lateral acceleration- will be published with the new L1 controller (#18810) in npfg_status. I would also find it nicer if we publish whatever we can in local_position_setpoint. That though also requires some controller interface alignment - using local coordinates prob is one thing of that.

Fully agreed! I think now that we have two controllers we can use this as an opportunity to clean up the controller interface

@Jaeyoung-Lim Jaeyoung-Lim merged commit bdec85f into master Jan 3, 2022
@Jaeyoung-Lim Jaeyoung-Lim deleted the pr-fw-local-pos-control branch January 3, 2022 10:09
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.

3 participants