There are difference between orb_id(actuator outputs) and orb id(actuator outputs sim)?

Preflight Fail in HITL with v1.13.0 · Issue #19667 · PX4/PX4-Autopilot · GitHub!

I was looking for that difference betweend ORB_ID(actuator_outputs_sim) and ORB_ID(actuator_outputs).

Then, This site attracted my interest.

void SimulatorMavlink::send()
{
#ifdef __PX4_DARWIN
	pthread_setname_np("sim_send");
#else
	pthread_setname_np(pthread_self(), "sim_send");
#endif

	// Subscribe to topics.
	// Only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS.
	_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs_sim), 0);

	// Before starting, we ought to send a heartbeat to initiate the SITL
	// simulator to start sending sensor data which will set the time and
	// get everything rolling.
	// Without this, we get stuck at px4_poll which waits for a time update.
	send_heartbeat();

	px4_pollfd_struct_t fds_actuator_outputs[1] = {};
	fds_actuator_outputs[0].fd = _actuator_outputs_sub;
	fds_actuator_outputs[0].events = POLLIN;

	while (true) {

		// Wait for up to 100ms for data.
		int pret = px4_poll(&fds_actuator_outputs[0], 1, 100);

		if (pret == 0) {
			// Timed out, try again.
			continue;
		}

		if (pret < 0) {
			PX4_ERR("poll error %s", strerror(errno));
			continue;
		}

		if (fds_actuator_outputs[0].revents & POLLIN) {
			// Got new data to read, update all topics.
			parameters_update(false);
			check_failure_injections();
			_vehicle_status_sub.update(&_vehicle_status);
			_battery_status_sub.update(&_battery_status);

			// Wait for other modules, such as logger or ekf2
			px4_lockstep_wait_for_components();

			send_controls();
		}
	}

	orb_unsubscribe(_actuator_outputs_sub);
}
void SimulatorMavlink::send_controls()
{
	orb_copy(ORB_ID(actuator_outputs), _actuator_outputs_sub, &_actuator_outputs);

	if (_actuator_outputs.timestamp > 0) {
		mavlink_hil_actuator_controls_t hil_act_control;
		actuator_controls_from_outputs(&hil_act_control);

		mavlink_message_t message{};
		mavlink_msg_hil_actuator_controls_encode(_param_mav_sys_id.get(), _param_mav_comp_id.get(), &message, &hil_act_control);

		PX4_DEBUG("sending controls t=%ld (%ld)", _actuator_outputs.timestamp, hil_act_control.time_usec);

		send_mavlink_message(message);

		send_esc_telemetry(hil_act_control);
	}
}

I’m conducting SILS (Software-In-the-Loop Simulation), and in the future, I want the motor speed in the simulation to match the actual motor speed in real-world conditions.

So, is there a difference between ORB_ID(actuator_outputs) and ORB_ID(actuator_outputs_sim)?

Here’s my understanding: The ORB_ID(actuator_outputs_sim) topic is the actuator output applied in simulations like Gazebo or jMAVSim.

On the other hand, I believe that the ORB_ID(actuator_outputs) topic is intended for HILS (Hardware-In-the-Loop Simulation). This is because, looking at the simulator_mavlink module, there are functions like send() and send_controls(). Following this code, it seems like the data is ultimately transmitted to HILS. Is that correct?

In other words, if it’s purely for simulation purposes, would it be sufficient to focus only on the ORB_ID(actuator_outputs_sim) topic?