Custom PX4 Multirotor "input_scaling" parameter

Hello, I am making a custom multirotor model in the sdf file and I am having trouble with the parameter “input_scaling”.

<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
  <robotNamespace/>
  <imuSubTopic>/imu</imuSubTopic>
  <magSubTopic>/mag</magSubTopic>
  <baroSubTopic>/baro</baroSubTopic>
  <mavlink_addr>INADDR_ANY</mavlink_addr>
  <mavlink_tcp_port>4560</mavlink_tcp_port>
  <mavlink_udp_port>14560</mavlink_udp_port>
  <serialEnabled>0</serialEnabled>
  <serialDevice>/dev/ttyACM0</serialDevice>
  <baudRate>921600</baudRate>
  <qgc_addr>INADDR_ANY</qgc_addr>
  <qgc_udp_port>14550</qgc_udp_port>
  <sdk_addr>INADDR_ANY</sdk_addr>
  <sdk_udp_port>14540</sdk_udp_port>
  <hil_mode>0</hil_mode>
  <hil_state_level>0</hil_state_level>
  <send_vision_estimation>0</send_vision_estimation>
  <send_odometry>1</send_odometry>
  <enable_lockstep>1</enable_lockstep>
  <use_tcp>1</use_tcp>
  <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
  <control_channels>
    <channel name='rotor1'>
      <input_index>0</input_index>
      <input_offset>0</input_offset>
      <input_scaling>1000</input_scaling>
      <zero_position_disarmed>0</zero_position_disarmed>
      <zero_position_armed>100</zero_position_armed>
      <joint_control_type>velocity</joint_control_type>
    </channel>
    <channel name='rotor2'>
      <input_index>1</input_index>
      <input_offset>0</input_offset>
      <input_scaling>1000</input_scaling>
      <zero_position_disarmed>0</zero_position_disarmed>
      <zero_position_armed>100</zero_position_armed>
      <joint_control_type>velocity</joint_control_type>
    </channel>
    <channel name='rotor3'>
      <input_index>2</input_index>
      <input_offset>0</input_offset>
      <input_scaling>1000</input_scaling>
      <zero_position_disarmed>0</zero_position_disarmed>
      <zero_position_armed>100</zero_position_armed>
      <joint_control_type>velocity</joint_control_type>
    </channel>
    <channel name='rotor4'>
      <input_index>3</input_index>
      <input_offset>0</input_offset>
      <input_scaling>1000</input_scaling>
      <zero_position_disarmed>0</zero_position_disarmed>
      <zero_position_armed>100</zero_position_armed>
      <joint_control_type>velocity</joint_control_type>
    </channel>
  </control_channels>
</plugin>

I’ve found out that iris model has input_scaling of 1000, solo with 1200, and typhoon with 1500. I am wondering why these values are different for each model and what this parameter means.

Sincerely,
Sang Hun

1 Like

@sanghun17 You can look at how the input scaling is used: PX4-SITL_gazebo/gazebo_mavlink_interface.cpp at 6b6f4749a74215b9a4fb81cfaa99a3950f13464d · PX4/PX4-SITL_gazebo · GitHub

The scale basically maps the normalized inputs [-1, …, +1] to something similar to the rotation speed values of the rotors, which gets consumed in the gazebo_motor_model. Therefore it should vary between models because the props have different thrust constants, and therefore spin at different RPMs.

Jaeyoung-Lim

I am trying to duplicate a real drone into to a realistic model that can run in SITL. I am currently using ROS and I can give throttle setpoing to the SITL vehicle, so I am not really sure why input_scaling is needed here. Perhaps, do I have to use the maximum value of input_scaling for this purpose (I’m guessing it is 10000)?

I am trying to duplicate a real drone into to a realistic model that can run in SITL. I am currently using ROS and I can give throttle setpoing to the SITL vehicle, so I am not really sure why input_scaling is needed here. Perhaps, do I have to use the maximum value of input_scaling for this purpose (I’m guessing it is 10000)?

The simulated motor model is expecting the rotational velocity of the motors. Therefore you need to scale your input so that it represents the rotor velocity: PX4-SITL_gazebo-classic/src/gazebo_motor_model.cpp at 1b1afca3440df678167818eaf8e38f301b16bcbd · PX4/PX4-SITL_gazebo-classic · GitHub

1 Like

@Jaeyoung-Lim

Hello again,

Like others i am trying to make my own model. I didn’t face with any issue with my quadrotors.

But for my tail mixer i am trying to do reduce yaw effect to %50 so in mixer file it’s something like this:

-----------------
M: 2
O:      10000  10000   0 -10000  10000
S: 1 1  9000   9000    0 -10000  10000
S: 1 2  -5000  -5000   0 -10000  10000

but when print deflection (In liftdrag_plugin.cpp/control angle(deg)) it is 25 degree. But logically it must be 12.5 degree.

Should i change my input_scaling for my tail too? I thought changing rotors input_scaling is enough for my model. Because deflection modelling probably same in other models?

Or are there any other way to do that?

Thanks.

Hello, if I have a controller that gives me thrust force in newtons, and I’m controlling body rates and throttle, and I’m using the iris quadcopter, would the following equations be sensible to give me the the desired throttle value from thrust?

motor_speed = sqrt(thrust / 4 * motorConstant)
throttle = (motor_speed - zero_position_armed ) / input_scaling