External motor control when using offboard mode

Hello, I am doing a project and the purpose of the project is to get PWM output from the “I/O PWM OUT” section while using the PX4 as a drone. I used the drone in offboard mode and generally my commands worked correctly.
Additionally, I connected 2 motors to the IO PWM OUT port of the drone and I need PWM to run these motors.

I set the MAIN 1 section on QGC to “offboard Actuator set 1”. When I test the actuator test section and examine the ANA1 section with an oscilloscope, I can get PWM output.
I run the codes below on the computer

sudo MicroXRCEAgent serial --dev /dev/ttyUSB0 -b 921600

code:

void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
{
	VehicleCommand msg{};
	msg.command = VehicleCommand::VEHICLE_CMD_DO_SET_ACTUATOR;
	msg.param1 = 1.0f;
    msg.param2 = 1.0f;
    msg.param3 = 1.0f;
    msg.param4 = 1.0f;
    msg.param5 = 1.0f;
    msg.param6 = 1.0f;
    msg.param7 = 0; // index
	// msg.target_system = 1;
	// msg.target_component = 1;
	// msg.source_system = 1;
	// msg.source_component = 1;
	// msg.from_external = true;
	msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
	std::cout << "Starting offboard control node..." << std::endl;

	vehicle_command_publisher_->publish(msg);
}

But there is no change in PWM waves on an oscilloscope in the MAIN 1 section.
Do I need to enable an additional parameter?
How can I make the “offboard actuator set 1” section produce PWM in the range I want via ROS2?


  • ROS2 Humble
  • Holybro Pixhawk 4

Topic output:

image

I had to arm it first for it to work, once I armed it it worked.

Would this work for Gimbal Roll, Gimba Pitch and Yaw selection? How to I select PWM AUX?

Yes it works with the use of VEHICLE_CMD_DO_MOUNT_CONTROL