PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.17k stars 13.36k forks source link

Support airspeed setpoint and position setpoint at the same time in offboard mode for Fixed Wing #21147

Open sunbeichen opened 1 year ago

sunbeichen commented 1 year ago

I want the offboard mode to support position setpoint and velocity setpoint at the same time.

Describe problem solved by the proposed feature

Recently I'm working on the offboard mode in Fixed Wing control. I found that SET_POSITION_TARGET_LOCAL_NED ( #84 ) only support the Copter/VTOL to set the airspeed. However, I want the FW to follow a set of points at different airspeeds.

Describe your preferred solution

Notice that the vx is ignored in SET_POSITION_TARGET_LOCAL_NED ( #84 ), the vx could be used to set the airspeed in this MAVLink message. As a result, the set position and set airspeed could be sent at the same frequency. Then the FW can follow the setpoint at desired airspeed.

Describe possible alternatives

Also, MAV_CMD_DO_CHANGE_SPEED (178 ) message could change the airspeed. However, when I use these two message at the same time, the FW didn't response to this change speed command. So alternatively, this bug could be handled to solve the problem.

Additional context

tstastny commented 1 year ago

Thanks for making the issue @sunbeichen - @sfuhrer and I have actually been discussing variable airspeed (and on a lower level appropriate control interfaces from offboard) very recently, and you've correctly identified some deficiencies in the current structure.

Can you provide a little more information how you are using offboard mode, what kind of vehicle, and what controllers (stock? custom?) you are intending to use on the FMU? Are you continuously streaming an airspeed setpoint (and position setpoints)? Or sending the aircraft to various distance positions with the intention to e.g. loiter? Will help determine what best strategy could be used to incrementally improve this interface for your application.

For MAV_CMD_DO_CHANGE_SPEED - you should note that commands aren't really intended to be continuously streamed, so if you want a continuous airspeed setpoint, I wouldn't recommend this method unless you are sparingly changing the speed command.

Maybe another note - are you using ROS? and have you been following the new ROS/PX4 bridge with XRCE micro dds? Could be another nicer avenue where we can start interfacing with uorb topics directly.

sunbeichen commented 1 year ago

Thank you @tstastny for the reply! I'm using a companion computer for this offboard mode. The vehicle is Standard Plane like the QGC provided. Controller is CUAV PIXHawk v6x and fmu-v6. I was streaming the position setpotion and airspeed setpoint together at 10Hz.

So this MAV_CMD_DO_CHANGE_SPEED command couldn't be used that frequently. That explains the no-respond phenomenon.

Sry I don't use ROS too much.

Octavian-Zhang commented 1 year ago

@sfuhrer I'm encountering the same issue: using SET_POSITION_TARGET_GLOBAL_INT cannot control fixed wing target airspeed. My application scenario is primarily on fixed-wing standard aircraft, intending to stream airspeed (MAV_CMD_DO_CHANGE_SPEED) and position (SET_POSITION_TARGET_GLOBAL_INT) setpoint simultaneously from a Raspberry Pi companion computer at several hertz. The position setpoint moves together with the plane at its front, such that this "setpoint" position will never be reached, it's only used as a heading and altitude control input reference. Additionally, I'm not using ROS, and my autopilot is FMUv6X with just standard PX4 software stack. Raspberry Pi companion computer program is proprietarily designed. @sunbeichen I also need to switch in and out from Offboard mode in flight, to use PX4 Takeoff/Land/Return/Hold together with our inhouse mission logic streamed from the companion computer during PX4 Offboard mode.

sfuhrer commented 1 year ago

I'm not the expert at all around offboard mode. @Jaeyoung-Lim is the only dev I know who's using it, maybe he has some advice. More likely though is that this won't be cleanly supported until we have the new mode API that's WIP atm.

Jaeyoung-Lim commented 1 year ago

@Octavian-Zhang @sunbeichen The velocity maginitude is not being used for offboard control, but only the tangent. The problem is that the SET_POSITION_TARGET_LOCAL_NED and SET_POSITION_TARGET_GLOBAL_INT are both defined in the inerital frame, and therefore the velocity means the ground velocity, not the airspeed.

If you want to do continuous airspeed control, this would need to be an added feature. Otherwise, you can use the MAV_CMD_DO_CHANGE_SPEED to chang the airspeed

@sunbeichen It is hard to imagine for me why you would want to do continuous airpseed regulation. Could you be able to elaborate why this is needed and what the expected behavior is? In case the vehicle receives a high airspeed setpoint, do you expect the vehicle to prioritize airspeed over altitude?

Octavian-Zhang commented 1 year ago

@Jaeyoung-Lim for my application, it is also OK to control ground velocity. However, SET_POSITION_TARGET_LOCAL_NED and SET_POSITION_TARGET_GLOBAL_INT doesn't affect the FIXED-WING ground speed setpoint, am I right?

Octavian-Zhang commented 1 year ago

@Jaeyoung-Lim for my application, it is also OK to control ground velocity. However, SET_POSITION_TARGET_LOCAL_NED and SET_POSITION_TARGET_GLOBAL_INT doesn't affect the FIXED-WING ground speed setpoint, am I right?

Since I read from this doc page that SET_POSITION_TARGET_LOCAL_NED affects Position setpoint (x, y, z only; velocity and acceleration setpoints are ignored).

Octavian-Zhang commented 1 year ago

@Jaeyoung-Lim for my application, it is also OK to control ground velocity. However, SET_POSITION_TARGET_LOCAL_NED and SET_POSITION_TARGET_GLOBAL_INT doesn't affect the FIXED-WING ground speed setpoint, am I right?

Since I read from this doc page that SET_POSITION_TARGET_LOCAL_NED affects Position setpoint (x, y, z only; velocity and acceleration setpoints are ignored).

In my understanding, the x and y in the Position setpoint (relative to the current aircraft location) act as fixed wing flight heading command, while the z in the Position setpoint works as flight altitude command, is this the case? If so, is there any way that ground speed command could be altered during fixed-wing offboard mode?

Jaeyoung-Lim commented 1 year ago

In my understanding, the x and y in the Position setpoint (relative to the current aircraft location) act as fixed wing flight heading command, while the z in the Position setpoint works as flight altitude command, is this the case?

Not really, it depends if you are sending the position setpoint together and then it is used as a tangent vector for path tracking for NPFG (The guidance controller). If you are only sending velocity setpoints, it only takes the heading.

https://github.com/PX4/PX4-Autopilot/blob/3bdb42b6a76e59eb936da0d2a01d734ee66d5320/src/modules/fw_path_navigation/FixedwingPositionControl.cpp#L1127-L1176

If so, is there any way that ground speed command could be altered during fixed-wing offboard mode?

As I already mentioned, you can use MAV_CMD_DO_CHAGE_SPEED. Otherwise you need to add support

Octavian-Zhang commented 1 year ago

For MAV_CMD_DO_CHANGE_SPEED - you should note that commands aren't really intended to be continuously streamed, so if you want a continuous airspeed setpoint, I wouldn't recommend this method unless you are sparingly changing the speed command.

@Jaeyoung-Lim Thanks for your timely reply, however, does MAV_CMD_DO_CHAGE_SPEED exhibit any problem as mentioned by @tstastny above? How fast can PX4 autopilot react to the MAV_CMD_DO_CHAGE_SPEED airspeed setpoint stream? I suspect that the following is the code snippet that responds to the MAV_CMD_DO_CHAGE_SPEED airspeed setpoint in the FixedwingPositionControl module, and I don't see why speed change can only be reacted at a limited rate.

https://github.com/PX4/PX4-Autopilot/blob/3bdb42b6a76e59eb936da0d2a01d734ee66d5320/src/modules/fw_path_navigation/FixedwingPositionControl.cpp#L231-L246

Jaeyoung-Lim commented 1 year ago

@Octavian-Zhang I think the more fundamental question is that does the TECS support continuous airspeed tracking. Getting the interface to support what you want is one thing, whether the current control scheme actually support your use case is another problem.

Why do you need to do continuous airspeed regulation to start with? Why not just add groundspeed support for the current interface?

Octavian-Zhang commented 1 year ago

@Jaeyoung-Lim but what do you mean by adding ground speed support for the current interface? Do you mean modifying the following snippet to let the adapt_airspeed_setpoint function accept Vector2f target_velocity vector magnitude as the second argument, replacing pos_sp_curr.cruising_speed?

https://github.com/PX4/PX4-Autopilot/blob/3bdb42b6a76e59eb936da0d2a01d734ee66d5320/src/modules/fw_path_navigation/FixedwingPositionControl.cpp#L1150-L1154

Jaeyoung-Lim commented 1 year ago

@Octavian-Zhang Yes

Octavian-Zhang commented 1 year ago

@Octavian-Zhang Yes

@Jaeyoung-Lim Thanks for the suggestion, however, I was wondering if there's still any way to stream vehicle altitude setpoint using FixedwingPositionControl::control_auto_velocity mode WITHOUT modifying the following line?

https://github.com/PX4/PX4-Autopilot/blob/3bdb42b6a76e59eb936da0d2a01d734ee66d5320/src/modules/fw_path_navigation/FixedwingPositionControl.cpp#L1146

Octavian-Zhang commented 1 year ago

@Octavian-Zhang Yes

@Jaeyoung-Lim Thanks for the suggestion, however, I was wondering if there's still any way to stream vehicle altitude setpoint using FixedwingPositionControl::control_auto_velocity mode WITHOUT modifying the following line?

https://github.com/PX4/PX4-Autopilot/blob/3bdb42b6a76e59eb936da0d2a01d734ee66d5320/src/modules/fw_path_navigation/FixedwingPositionControl.cpp#L1146

Note that vertical velocity setpoint pos_sp_curr.vz is not used at all in FixedwingPositionControl::control_auto_velocity

Jaeyoung-Lim commented 1 year ago

Note that vertical velocity setpoint pos_sp_curr.vz is not used at all in FixedwingPositionControl::control_auto_velocity

This is not true: https://github.com/PX4/PX4-Autopilot/blob/3bdb42b6a76e59eb936da0d2a01d734ee66d5320/src/modules/fw_path_navigation/FixedwingPositionControl.cpp#L1165-L1175

@Octavian-Zhang Could you tryout https://github.com/PX4/PX4-Autopilot/pull/21211 ?