Fixed-wing offboard actuator control

Hi guys, I am trying to figure out how to control the actuators of a fixed-wing offboard. At the moment i am working in Gazebo, with mavros on PX4 1.9. Sadly i don’t really see a good solution yet.

Ideas that i have at the moment:

  1. Preferred option Use the script manual_input.py from the Firmware github to immitate remote control inputs. I found a similar file for cpp on here, but it seems to be old.
  2. Use the QGroundControl code that imitates a joystick and send joystick commands over the UDP port 14570 (see figure on here)

Do you have any better ideas? If you think one of my ideas are suitable, which one? Could you give me some hints or point me towards how i can proceed to get it working?

@vwueest Could you explain why you chose to control actuator setpoints? There are higher level commands that you can use already as you can see in this doc

@Jaeyoung-Lim We are doing a research project, where we need to control on the lowest level possible. We would like to skip all PID controllers, to have full control of the vehicle. So for attitude, we would like to be able to set the angular acceleration (omega_dot) or the set the position of the control surfaces (u) directly.


Since that’s essentially what remote control inputs do, i thought we can achieve that with idea 1. that i mentioned. However, i have the impression the code is deprecated (please correct if I’m wrong).
The other option is to do something similar to “Virtual Joystick” in QGroundControl.
Please let me know if you have any better ideas or tips on how to proceed. Thanks a lot

I did some more research on the topic. It seems that i can achieve just that by using the mavros topic /mavros/rc/overrice. However, i did not really find any documentation on it and did not see any effects when I did the following:

  1. clone firmware, checkout version v1.9.2
  2. run Gazebo with ROS wrapper as described in the px4 documentation (link), but adapt it to run the plane instead of the iris quad
  3. Take off, put it in manual mode and published: rostopic pub -r 10 /mavros/rc/override mavros_msgs/OverrideRCIn '[2000, 2000, 2000, 2000, 2000, 2000, 2000, 2000]'
  4. In the PX4 shell i see the message RC_CHANNELS message detected! come up, but there is no effect visible (propeller off, all control surface to initial position)
    How does RC override work? Are there parameters I have to set that i have to set? Does anybody have experience with this?
    Thanks for your help!

@vwueest Just as a note, the RC controls do not control the acceleration setpoints as you mentioned, but the actuator inputs.

On fixed wing the relationship with acceleration setpoint and actuator input is nonlinear and this is why using higher level outputs generally result in better control tracking since the flight controller takes care of the input tracking.

@Jaeyoung-Lim yes you are right. Thanks for the note
We would still like to control the actuators eventually, as we are trying to combine low and high level control commands into one as a research project.
It seems that rc/override is not recommended and does not work for me yet. Is there another way I can achieve this, any tips? Maybe with these topics: actuator_control, manual_control/send? I myself did not have any success yet. Please let me know if anyone did or has an idea how

In the meantime I have tried to send higher level commands (I tried setpoint_position/local, setpoint_raw/attitude & mavros/setpoint_velocity/cmd_vel) as you suggested. They work well on the iris quadrotor, but I don’t have any success on the gazebo plane in PX4 v1.9.2. I can switch to offboard mode, but the plane just keeps doing what it was or even sets all actuators to the initial state when sending attitude/thrust comands (sets thrust to 0 for some reason).

Because i once read offboard was not supported in that version, I wanted to try v1.10. There are 2 issues that came up:

  1. When i freshly clone the firmware, check it out at v1.10.0-beta4, and try to build it with make px4_sitl_default gazebo_plane, the build crashes with the output:
[ 28%] Building CXX object msg/CMakeFiles/uorb_msgs.dir/topics_sources/wind_estimate.cpp.o
[ 28%] Linking CXX static library libuorb_msgs.a
[ 28%] Built target uorb_msgs
CMakeFiles/Makefile2:20225: recipe for target 'platforms/posix/CMakeFiles/gazebo_plane.dir/rule' failed
make[2]: *** [platforms/posix/CMakeFiles/gazebo_plane.dir/rule] Error 2
Makefile:6205: recipe for target 'gazebo_plane' failed
make[1]: *** [gazebo_plane] Error 2
Makefile:193: recipe for target 'px4_sitl_default' failed
make: *** [px4_sitl_default] Error 2
exit 2

(I am running Ubuntu 18.04.3, ROS melodic, Gazebo 9.0.0)

  1. I found this commit from you @Jaeyoung-Lim. I tried to copy these changes into v1.9.2, to allow offboard mode for fixed wings in v1.9.2. Even then, same results as mentioned above.

How can i use command the plane? Am i missing somethings? It feels like this should not be that hard. Any help appreciated

@vwueest SITL is failing due to the wrong target name. Try

make px4_sitl gazebo_plane

I actually never tried actuator_control messages on fixed wing. Would be interesting to see if it works.

@Jaeyoung-Lim the build also crashes with the same error message when I checkout v1.10.0-beta4 and run

make px4_sitl gazebo_plane 

Do you have an example you could point me to about actuator_control? I tried publishing on /mavros/actuator_control and /mavros/target_actuator_control. Neither had an effect on the plane

Can you run sitl for multirotors? It seems like you are missing something to run SITL. It works for me fine.

/mavros/target_actuator_control is a published topic from mavros so you won’t have any effect.

To use /mavros/actuator_control make sure you set the right group_mix as defined here: http://docs.ros.org/api/mavros_msgs/html/msg/ActuatorControl.html

A) compilation

  • v1.9.2: SITL compiles and works for plane & quadrotor. Offboard only works for quadrotor
  • v1.10.0: does not compile (none of the beta or rc) on my system (Ubuntu 18.04.3, ROS melodic, Gazebo 9.0.0). All make commands (make px4_sitl gazebo, gazebo_plane, gazebo_iris) fail with the same error message:
-- Found GStreamer: adding gst_camera_plugin                                                                                                                                                                
[ 13%] Building CXX object msg/CMakeFiles/uorb_msgs.dir/topics_sources/commander_state.cpp.o                                                                                                                
-- Found GStreamer: adding gst_video_stream_widget                                                                                                                                                          
CMake Error: The following variables are used in this project, but they are set to NOTFOUND.                                                                                                                
Please set them or make sure they are set and tested correctly in the CMake files:                                                                                                                          
GSTREAMER_LIBRARIES (ADVANCED)                                                                                                                                                                              
    linked by target "LiftDragPlugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                          
    linked by target "gazebo_video_stream_widget" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                              
    linked by target "gazebo_gst_camera_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                
    linked by target "gazebo_barometer_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                 
    linked by target "gazebo_magnetometer_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                              
    linked by target "gazebo_multirotor_base_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                           
    linked by target "gazebo_motor_model" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                      
    linked by target "gazebo_mavlink_interface" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                
    linked by target "gazebo_gimbal_controller_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                         
    linked by target "physics_msgs" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                            
    linked by target "nav_msgs" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                                
    linked by target "gazebo_wind_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                      
    linked by target "gazebo_imu_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                       
    linked by target "std_msgs" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                                
    linked by target "gazebo_opticalflow_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                               
    linked by target "gazebo_sonar_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                     
    linked by target "sensor_msgs" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                             
    linked by target "gazebo_gps_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                       
    linked by target "mav_msgs" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                                
    linked by target "gazebo_irlock_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                    
    linked by target "gazebo_lidar_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                     
    linked by target "gazebo_uuv_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                       
    linked by target "gazebo_vision_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                                    
    linked by target "gazebo_geotagged_images_plugin" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                          
    linked by target "gazebo_controller_interface" in directory /home/valentin/temp3/Firmware/Tools/sitl_gazebo                                                                                             
                                                                                                                                                                                                            
-- Configuring incomplete, errors occurred!                                                                                                                                                                 
See also "/home/valentin/temp3/Firmware/build/px4_sitl_default/build_gazebo/CMakeFiles/CMakeOutput.log".                                                                                                    
See also "/home/valentin/temp3/Firmware/build/px4_sitl_default/build_gazebo/CMakeFiles/CMakeError.log".                                                                                                     
platforms/posix/CMakeFiles/sitl_gazebo.dir/build.make:105: recipe for target 'external/Stamp/sitl_gazebo/sitl_gazebo-configure' failed                                                                      
make[4]: *** [external/Stamp/sitl_gazebo/sitl_gazebo-configure] Error 1                                                                                                                                     
CMakeFiles/Makefile2:14156: recipe for target 'platforms/posix/CMakeFiles/sitl_gazebo.dir/all' failed                                                                                                       
make[3]: *** [platforms/posix/CMakeFiles/sitl_gazebo.dir/all] Error 2                                                                                                                                       
make[3]: *** Waiting for unfinished jobs....        

B) Is there something else I have to do besides publishing on the actuator_control topic? Do I have to switch to OFFBOARD mode? Are there parameters to be set?
When i publish actuator_control and then switch to

  • MANUAL: no effect, all actuators go to their zero position/throttle
  • OFFBOARD: the simulation freezes (quadrotor & plane)

I set group_mix to PX4_MIX_FLIGHT_CONTROL and also tried PX4_MIX_MANUAL_PASSTHROUGH - no effect.

Update regarding problems stated earlier

A)
We found the solution: https://github.com/PX4/Firmware/issues/13416
It is a gstreamer related issue. We solved it by running:

sudo apt install libgstreamer1.0-dev
sudo apt install gstreamer1.0-plugins-good
sudo apt install gstreamer1.0-plugins-bad
sudo apt install gstreamer1.0-plugins-ugly

B) not resolved

2 Likes

Update on B)

Solution found
When sending commands on actuator_control in PX4 v1.10 & master, this info shows up:

ERROR [mavlink] SET_ACTUATOR_CONTROL_TARGET not supported with lockstep enabled
ERROR [mavlink] Please disable lockstep for actuator offboard control:
ERROR [mavlink] https://dev.px4.io/master/en/simulation/#disable-lockstep-simulation

I followed these instructions and now am able to control the actuators when doing this:

  • publish on the mavros topic actuator_control
  • switch to offboard mode

However
When i follow these instructions to disable lockstep, I repetedly get accelerometer and gyroscope error messages:

[ERROR] [1575971113.545578414, 142.656000000]: FCU: Accel #0 fail:  TIMEOUT!
[ERROR] [1575971113.595938207, 142.656000000]: FCU: Gyro #0 fail:  TIMEOUT!
ERROR [sensors] Accel #0 fail:  TIMEOUT!
ERROR [sensors] Sensor Accel #0 failed. Reconfiguring sensor priorities.
WARN  [sensors] Remaining sensors after failover event 0: Accel #0 priority: 1
ERROR [sensors] Gyro #0 fail:  TIMEOUT!
ERROR [sensors] Sensor Gyro #0 failed. Reconfiguring sensor priorities.
WARN  [sensors] Remaining sensors after failover event 0: Gyro #0 priority: 1

I looked at the CPU usage and my computer was not even close to its limits in any of the cores. I think there must be another issue, which seems to be related to disabling the lockstep. Is this a bug in the firmware? How could i solve this issue? Let me know if you have any ideas please

Did you find any solution to the accelerometer and gyroscope error messages?

I am also trying to send actuator_control values (in JMAVSim simulation) in offboard mode by disabling lockstep but I get these error messages. I have also observed that the quad is less stable than with lockstep enabled and it drifts drastically when exiting offboard mode.

Yes, I did kind of find a solution. I left the lockstep enabled, used PX4 V1.10.1 and have tested it also on v1.10.0-rc3. The essential thing is that you have to publish at >=150Hz, otherwise the lockstep locks the simulation.
So what I did is, I sent actuator controls like this:

rostopic pub /mavros/actuator_control mavros_msgs/ActuatorControl "header:
  seq: 0
  stamp: {secs: 0, nsecs: 0}
  frame_id: ''
group_mix: 0
controls: [0.3, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0]" -r 200

and then set the vehicle to offboard mode:

rosservice call /mavros/set_mode "base_mode: 0custom_mode: 'OFFBOARD'"

That’s it, this worked in the Gazebo simulation for me. Hope it helps

I tried your solution on PX4 v.10.1 with lockstep enabled, but I am getting the error

ERROR [mavlink] SET_ACTUATOR_CONTROL_TARGET not supported with lockstep enabled
ERROR [mavlink] Please disable lockstep for actuator offboard control:
ERROR [mavlink] Simulation · PX4 Developer Guide

I am using a cpp node to publish commands at 200 Hz to the topic /mavros/actuator_control. I tried it on both Gazebo and JMAVSim, but PX4 is not accepting the actuator control messages.

Are you using command line to publish the messages and set offboard mode?

I tried again and you’re right in that it didn’t work for me anymore. However, i didn’t see these errors. It could have to do with some parameter setting.

I was able to get it running by starting the sim with this launch file:

<?xml version="1.0"?>
<launch>
    <!-- MAVROS posix SITL environment launch script -->
    <!-- launches MAVROS, PX4 SITL, Gazebo environment, and spawns vehicle -->
    <!-- vehicle pose -->
    <arg name="x" default="0"/>
    <arg name="y" default="0"/>
    <arg name="z" default="0"/>
    <arg name="R" default="0"/>
    <arg name="P" default="0"/>
    <arg name="Y" default="0"/>
    <!-- vehicle model and world -->
    <arg name="est" default="ekf2"/>
    <arg name="vehicle" default="plane"/>
    <arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
    <arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/plane/plane.sdf"/>

    <!-- gazebo configs -->
    <arg name="gui" default="false"/>
    <arg name="debug" default="false"/>
    <arg name="verbose" default="false"/>
    <arg name="paused" default="false"/>
    <arg name="respawn_gazebo" default="false"/>
    <!-- MAVROS configs -->
    <arg name="fcu_url" default="udp://:14540@localhost:14557"/>
    <arg name="respawn_mavros" default="false"/>
    <!-- PX4 configs -->
    <arg name="interactive" default="true"/>
    <!-- PX4 SITL and Gazebo -->
    <include file="$(find px4)/launch/posix_sitl.launch">
        <arg name="x" value="$(arg x)"/>
        <arg name="y" value="$(arg y)"/>
        <arg name="z" value="$(arg z)"/>
        <arg name="R" value="$(arg R)"/>
        <arg name="P" value="$(arg P)"/>
        <arg name="Y" value="$(arg Y)"/>
        <arg name="world" value="$(arg world)"/>
        <arg name="vehicle" value="$(arg vehicle)"/>
        <arg name="sdf" value="$(arg sdf)"/>
        <arg name="gui" value="$(arg gui)"/>
        <arg name="interactive" value="$(arg interactive)"/>
        <arg name="debug" value="$(arg debug)"/>
        <arg name="verbose" value="$(arg verbose)"/>
        <arg name="paused" value="$(arg paused)"/>
        <arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
    </include>
    <!-- MAVROS -->
    <include file="$(find mavros)/launch/px4.launch">
        <!-- GCS link is provided by SITL -->
        <arg name="gcs_url" value=""/>
        <arg name="fcu_url" value="$(arg fcu_url)"/>
        <arg name="respawn_mavros" value="$(arg respawn_mavros)"/>
    </include>
</launch>

Hope this works for you. I am not entirely sure what’s the difference between the roslaunch px4 posix_sitl.launch vehicle:= plane and my launch file, but my file worked for the plane, while the px4 official one did not.

Hey,
I tried all of these, still its not working. I have created a new issue (here)[Not able to set actuator controls for fixed wing in SITL].
How did it work for you? Am I missing something?.
Any help will be appreciated

Continuing the discussion from Fixed-wing offboard actuator control:

Have you solved the problem? I also tried all methods above but there’s still error:

ERROR [mavlink] SET_ACTUATOR_CONTROL_TARGET not supported with lockstep enabled
ERROR [mavlink] Please disable lockstep for actuator offboard control:
ERROR [mavlink] Simulation · PX4 Developer Guide