Publishing into actuator_controls_0 troubles

I am going to write a test application for direct control of motors of Vtol (in gazebo simulation). The problem begins when I am trying to advertise actuator_controls_0 in the program. The most simplified version of my program is

#include <uORB/topics/actuator_controls.h>
#include <string.h>

extern "C" __EXPORT int test_control_main(int argc, char *argv[]);

int test_control_main(int argc, char *argv[])
{
    actuator_controls_s actuators;
    memset(&actuators, 0, sizeof(actuators));
    orb_advert_t actuator_pub = orb_advertise(ORB_ID(actuator_controls_0), &actuators);
    return actuator_pub == nullptr ? -1 : 0;
}
px4_add_module(
	MODULE examples__test_control
	MAIN test_control
	STACK_MAIN 2000
	SRCS
		main.cpp
	DEPENDS
)

Before launching I disabled all the controllers mc_att_control mc_pos_control fw_att_control fw_pos_control_l1 in the file rc.vtol_apps. I launch the simulator by

make px4_sitl gazebo_standard_vtol

and after

pxh> test_control
[Err] [gazebo_mavlink_interface.cpp:1018] poll timeout
[Err] [gazebo_mavlink_interface.cpp:1018] poll timeout

I also tried to launch the examples hwtest, and uuv_example_app. There is the same error.
I use px4 of master 6d2849f4ef5e50a8806e445c6e1071fd28741648, Gazebo7, and Ubuntu 16.

This is somewhat expected. Let me try to explain what is going on.

We recently added lockstep to SITL. What this means is that the time of px4 is set by the simulator (jMAVSim or Gazebo). The way this works is that the simulator sends a HIL_SENSOR mavlink message including sensor data and a timestamp and then waits until it receives a HIL_ACTUATOR_CONTROLS message back.

At the beginning until this is initialized, the simulator “freewheels”, so it sends HIL_SENSOR until it receives HIL_ACTUATOR_CONTROLS. Then it expects a HIL_ACTUATOR_CONTROLS for every HIL_SENSOR or otherwise times out saying poll timeout as you see it.

Therefore, you have at least 2 possibilities to make this work:

  1. You implement continuously publishing actuators (which trigger sending HIL_ACTUATOR_CONTROLS) on each sensor_combined (from gyro_sensor) topic that has been published like it is done in the normal SITL architecture. That way it should keep flowing. And make sure to use px4_poll on the topic, so you never miss one.

  2. Disable lockstep:
    Set this to no: https://github.com/PX4/Firmware/blob/9782aecc73b45ae72ce01e507b1535c43f3780b6/boards/px4/sitl/default.cmake#L102

Thank you.
If I understood correctly, to solve my problem I need to implement a (real-time?) loop within which I read all the messages from gyro (is gyro only enough?), and send the necessary control values to the motors.
I would like to ask you if there is a basic implementation? For now I rely on mc_att_control_main.cpp.

For multicopters, there are two paths through the system which can be confusing:

simulator_mavlink -> [sensor_gyro] -> sensors -> [sensor_combined] -> ekf2 -> [...] -> mc_pos_control -> [] -> mc_att_control -> [actuator_controls] -> pwm_out_sim -> [actuator_outputs] -> simulator_mavlink
simulator_mavlink -> [sensor_gyro] -> mc_att_control -> [actuator_controls] -> pwm_out_sim -> [actuator_outputs] -> simulator_mavlink

As long as one of the two makes it through, the simulation loop will keep going. And it doesn’t really need to be realtime. The point of lockstep is that either side can pause and the other side will just wait for the next sample. This allows breakpoints with GDB or stalls if the CPU is too busy.

Hey @JulianOes and @Maksim_Surov
I’ve been facing a similar problem. I am new to this and I started learning from the First Application Tutorial in the PX4 guide.
I understand how to subscribe to topics and read messages but I cannot seem to be able to publish to the necessary topic in order to actually control the quad in JMAVSim through my code. I tried publishing to the vehicle_attitude_setpoint topic to control the attitude of the quad but that didn’t seem to work, My code is similar to the final code [here](https://docs.px4.io/main/en/modules/hello_sky.html). I’ve added the following in order to publish to the vehicle_attitude_control topic—>


    struct vehicle_attitude_setpoint_s att;
	memset(&att, 0, sizeof(att));
	orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att);

    att.q_d[0] = 1.5;
	att.q_d[1] = 2.6;
	att.q_d[3] = 2.7;
    att.q_d[4] = 1.7;

	orb_publish(ORB_ID(vehicle_attitude_setpoint), att_pub, &att);

What should I do to be able to control and move the quad around in JMAVSim using the application that I am writing in C?