Control of Individual Motors/Actuators

Platform details:

  • PX4 v1.14
  • Pixhawk v6x
  • Ubuntu 22.04
  • ROS2 Humble

Using the above software/hardware, our research group at UC Berkeley is attempting to control the motors on our quadcopter in offboard mode using a companion laptop. We want to control the specific PWM values or throttle percentages of the motors, control the length of time the motors run at that value, and we would like to be able to control individual motors.

Using QGC to manually control the motors, we can individually control any motor or all motors with full power accurately.
However, we cannot achieve this functionality otherwise. When running code, The motors do not run at the throttle percentage or PWM value we specify in the code, often running at a much slower speed than the value we specified in the code. They also will still run when we specify 0.0 or NaN or -1.0 input, which should not happen according to PX4 generic actuator control documentation. The motors all run at the exact same speed as one another every time, even when we specify different values for different actuators.

We have been rewriting and testing numerous versions of code based on the offboard_control.cpp code example file provided by the PX4 GitHub, but nothing has succeeded in controlling the motors as expected.
We have attempted to utilize ActuatorMotors messages, and VehicleCommand messages with VEHICLE_CMD_DO_SET_ACTUATOR as well as VEHICLE_CMD_DO_MOTOR_TEST. We have tried countless different parameter values for all of these functions, and have tried various values for target_system, target_component, source_system, and source_component in the publish_vehicle_command function. We have also tested various OffboardControlMode message parameter values, including setting msg.direct_actuator to true and everything else false. We have ensured that the topics “fmu/in/actuator_motors” and “fmu/in/actuator_servos” are listed under subscriptions in the dds_topics.yaml file. We have echoed the “fmu/out/vehicle_control_mode” topic and ensured that the control allocation flag is false. We tested setting AUX 1 - AUX 4 in QGC to “Motor X” as well as “Offboard Actuator Set X”. None of this has succeeded.

How do we control our motors/servos/actuators at specified inputs? And how do we do this for individual motors rather than all at once?

Hi,

I don’t know if you already solved this problem, but in the most recent version of PX4, the ActuatorMotors.msg has its own ROS2 topic. Thus it is simple to specify the thrust level of any motor individually.

I do this with the r1_rover model. If you look at the iris airframe at /ROMFS/px4fmu_common/init.d-posix/airframes/10015_gazebo-classic_iris you can see the following parameters:

param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

This tell that 4 values needs to be given to ActuatorMotors.control, one for each motor (101, 102, 103, 104). You can check the motor order in the sdf file of the iris model, under the mavlink plugin <control_channels> part (look at <input_index> where the joint with lower value is the PWM_MAIN_FUNC1 101 and so on). As you know, you have to give values in the [-1, 1] range, where 1 is maximum positive thrust and -1 is maximum negative thrust (the negative part can be enable if supported by the model, or you can enable it using the ActutorMotors.reversible_flags [set this value as a series of 1 and 0 where 1 means reversibility ON, whereas 0 means OFF. To have reversibility on all 4 motors, just set reversible_flags = 1111]).

This gives you a complete control on the thrust level of each of the 4 motor.