Offboard control with Attitude and Velocity or Position for Z control

Is it possible to create a method to command PX4 using offboard mode with attitude for roll, pitch, yaw and position or velocity command for Z instead of thrust?

Have you considered using MAVSDK? Check the API for offboard here:
https://mavsdk.mavlink.io/develop/en/api_reference/classmavsdk_1_1_offboard.html

Yes I am already looking into MAVSDK. But the main problem I have is that the command structures dont have the combination I am looking for.

For example,
the struct Attitude has roll, pitch, yaw and thrust
instead, I was looking for a struct that has roll, pitch, yaw and down_velocity

Right, so you would basically want the same interface as ALTCTL. I think this would have to be added to the offboard plugin. Would you be interested in making a pull request to add it?

Yes I would like to add it. I think that this will need a new MAVlink message (having roll, pitch, yaw and down_velocity) which means that PX4 also has to be changed for this new message.

Do you see any way of doing this without a new MAVlink message?

Could we assemble it using the existing messages? Presumably we have to send two messages but it should work.

Actually, taking a step back: why do you need roll/pitch/yaw instead of velocities?

I had tried sending two messages but it didn’t work as I wanted.
I created 2 functions in MAVSDK. One sends just the down_speed by using position_setpoint message in MAVlink (everything else other than down_speed was ignored using the ignore mask) and other which sends just the quaternion using the attitude_setpoint message in MAVlink (everything else other than the quaternion was ignored using the ignore mask). But this did not work as I wanted.

The application for which I am working on this modifications includes the operation of a drone in close proximity to big structures which demand a fine control. I already have a high level control ready and working which commands roll, pitch and yaw to the drone with an another flight controller stack. but I am planning to move to PX4 for better flexibility in modifications.

Ok, I understand. If the flight controller has good localization / position estimation then velocity control should work equally well though, at least if tuned well.

Agreed. But it is kinda an unknown which I wanted to eliminate which is why I decided to go about the atti commands.
Coming back to sending the mixed command of attitude and velocity. I was not able to use 2 commands to command atti in one and velocity in the other one. maybe I am doing it in a wrong way! Any comments on that?

I would have to try that and debug in the Firmware what exactly happens. Unless @MaEtUgR knows?

Ok. I am trying it on my side by adding a new MAVlink message but it would be good to know if there is an easier way.

I don’t think an additional messages resolves it. It rather needs fixing in the controllers where the data is consumed.

Oh! Do you mean the controllers inside PX4 firmware?

Yes that’s what I mean.

I guess the mc_att_control module might need changes to use z velocity instead of thrust. It will be quite a modification! Please let me know if you find out anything!

1 Like

I’m not sure what interface is supported in offboard mode but coming from the RC side what you want to have is basically altitude mode just controlled by an offboard computer instead of a remote.

The multicopter attitude controller “only” controlls the attitude and not velocity which is done in the position controller so adding velocity control to the module does not make sense architecturally. What’s done in altitude mode is setting the thrust vector direction from the right stick and generating the thrust vector length according to the velocity controller output (with velocity setpoint from the left stick up/down). PX4-Autopilot/src/lib/FlightTasks/tasks/ManualAltitude/FlightTaskManualAltitude.cpp at e4509486e82034dc8fdc172c42ec2ac84ed1ee1c · PX4/PX4-Autopilot · GitHub To achieve that there’s actually a bit of a hack in the position controller PX4-Autopilot/src/modules/mc_pos_control/PositionControl.cpp at e4509486e82034dc8fdc172c42ec2ac84ed1ee1c · PX4/PX4-Autopilot · GitHub which I’m currently refactoring in [WIP] Intuitive manual position control by mapping stick input to acceleration by MaEtUgR · Pull Request #12072 · PX4/PX4-Autopilot · GitHub to allow sideways acceleration input which conceptually is a scaled attitude tilt and would probably work for your needs.

When that’s finished I think it should be easy to just enable or even just test acceleration setpoints through the offboard interface and you could run your desired offboard control.

The documentation was updated recently: http://docs.px4.io/master/en/flight_modes/offboard.html#coptervtol

Right now you can’t do what you want, i.e. mix attitude and position.
If you want to implement it, the best way is to use the already present MAVlink messages and add the correct type_mask to the messages.

The alternative is that you do the vertical control loop offboard and you command the thrust to the copter.

I am looking forward to the changes you are planning to do.
I exactly want to do what you mentioned with respect to the RC controlling the altitude by the throttle stick and the other stick controlling the attitude.
Is there a way to use the Manual Altitude Flight Task (or ALTCTL mode) with offboard mode which will allow me to atleast set a fixed height and then send attitude commands to control the attitude?

Also, what is the timeline for the acceleration setpoints to be introduced?

@krunal2103 I wanted to quickly check in on the status:
I consider https://github.com/PX4/Firmware/pull/12072 stable now and it’s in the last testing and review phase and will not get any bigger changes anymore. We will probably hold it back until after the 1.10.0 PX4 release because it’s considered to risky to merge just before the release. Once that’s in we can easily expose the new interface with arbitrary acceleration, velocity, poosition setpoint combinations over all dimensions to offboard users.

I hope that helps. Let me know if you’d be interested in testing a draft implementation of that interface.

@MaEtUgR I am glad to know that the acceleration setpoint feature is in the last phase of testing. As of the changes I was going to make, I have made some changes which is working in the SITL gazebo sim.
The following is the overview of my changes:

  1. I made a new mavlink message which contains the attitude in the form of quaternion and velocity in z direction.
  2. Made a new function in mavlink_receiver to handle the new mavlink message. This function modifies the position_setpoint_triplet topic with zero velocity in x and y and z velocity equal to the value received by the new message.
  3. Now, the mc_pos_control thinks that there are velocity setpoints coming through which generates thrust and yaw setpoints using these velocity setpoints.
  4. I then add my desired attitude received through the new message to the attitude that is calculated using the generated thrust and yaw setpoints. This new attitude is then publishes to the attitude_setpoint topic which is then used my mc_att_control to generate actuator commands.

This has to be still tested on the aircraft.

With respect to testing a draft implementation of the interface you implemented, I would love to do that!
Let me know what you think about my approach and what should I do to test your implementation.