Thrust and Torque constants in TOML geometry description and SITL gazebo models

Hi! I wondering what’s are the units for Ct and Cm and what is the formulae used to calculate Torque and Thrust with those terms?

I see Ct (thrust constant) has values about 1.0. While Cm (torque constant) has values about 0.05.

While Torque constant in SITL Gazebo models are in the same range. So called motorConstant used in Gazebo is several orders of magnitude smaller than Ct.

In Gazebo plugin the formula for Thrust as follows

F = motor_constant * real_motor_velocity^2
where real_motor_velocity is in radians/sec.

Looks like TOML uses different units for angular velocity of motor - maybe RPM (revoluts per minute)?
Does it have still same quadratic dependance of Thrust other the RPM?

Is this stuff documented anywhere?

For example standard_vtol.sdf used in SITL gazebo has

motorConstant = 8.54858e-06

At the same time it uses “4x” key in mixer file to control its quad rotor part.

“4x” geometry is defined in “quad_x.toml” file where Ct = 1.0

And Im struggling to find any correlation between 8.54858e-06 and 1.0. Which are the units? What are the formulas?

Hi,

Short answer:
At the moment these constant do not have a big effect. Only the ratio between Ct and Cm is important.

Longer answer:
Ct is in Newton/command, it is the thrust at command 1 (max command).
Cm is in Newton.meter/command, it is the torque at command 1 (max command).

The formula is different from gazebo in that it does not use motor velocity but motor command which is between 0 and 1: F = motor_constant * motor_command
You can find the formulas used to compute the thrust here px_generate_mixers.py#L150-L157, and the one for the torque here: px_generate_mixers.py#L127-L134.

Also, the mixers are currently normalized px_generate_mixers.py#L191-L218 so

  • the absolute values of Ct and Cm do not matter much
  • the ratio between Ct and Cm is important if the rotors are not all horizontal
  • if your platform have motors stronger than others, you can reflect it by setting larger Cts and Cms for the stronger motors

In the future I hope we can use non-normalized mixers so that Ct and Cm have more physical meaning.

Hi @jlecoeur!

Thank you for your detailed explanation.

You are saying: [quote=“jlecoeur, post:3, topic:5986”]

  • the ratio between Ct and Cm is important if the rotors are not all horizontal
    [/quote]

Does that implies that having all motors horizontal those numbers dose not matter at all?

Also I would like to notice couple of differences between conventions used in TOML geometry description and SITL gazebo.

  1. Formulae in Gazebo has quadratic dependance of Thrust over the angular velocity. While according to your description control uses linear dependance.
  2. Gazebo uses Z axis directed upwards while TOML describes geometry with Z pointing down.

You are welcome.

Yes pretty much.

  1. The difference is that PX4 mixers do not output angular velocity, but motor command between 0 and 1. This is then converted to a PWM signal. The non-linear mapping between PWM and thrust is corrected as of https://github.com/PX4/Firmware/pull/5287.

  2. Gazebo uses Z up and Y left, while PX4 uses Z down and Y right.

Hi @jlecoeur!

Working with simulation I noticed strange thing.

As Z axes in Gazebo and TOML are pointing different directions I expect rotations should be different as well. For example CCW rotation in Gazebo about Z pointing upwards should be described in TOML as CW rotation about Z pointing downwards.

BUT. As I running my simulation I see my drone rotates about its vertical axis if I following that rule.

And if I use the same rotations in both files it flies ok.

Could you please explain. Am I correct in my considerations?

For example looking at “iris” model.

In its SDF file “front_right_motor_model” has “turningDirection” set to “ccw”.

At the same time its init script loads mixer named quad_w_main.mix which in turn uses “4w” geometry described in “quad_wide.toml” where “front_right” motor has same CCW rotation direction.

Isn’t there some (double) error which makes this work correctly while it should not?

@jlecoeur thanks for the explanations of CT/Cm

I’m currently trying to build an experimental VTOL geometry as you can see above (you can see pics and video on social medias @avioneo or www.avioneo.com)

the question is, as the tilt wings move between Hover to FW, how do I describe the geometry? Also The CG is moving not only during the transition but also when YAW in hover and ROLL in FW…

But first, what do you think about my .toml file ?

Thx,

Penta Avioneo eVTOL duo coax C/R on dif tiltwings + light1/10 front pitch turbine

[info]
key = “5A”
description = “Penta Avioneo eVTOL duo coax C/R on dif tiltwings + light1/10 front pitch turbine”

[rotor_default]
axis = [0.0, 0.0, -1.0]
Ct = 0.5
Cm = 0.025
direction = “CCW”

[[rotors]]
name = “1-rear_righ_top”
position = [-0.02, 0.975, 0.2]

[[rotors]]
name = “2-rear_right_bot”
position = [-0.02, 0.975, 0.165]
direction = “CW”

[[rotors]]
name = “3-rear_left_up”
position = [-0.02, -0.975, 0.2]

[[rotors]]
name = “4-rear_left_bot”
position = [-0.02, -0.975, 0.165]
direction = “CW”

[[rotors]]
name = “5-front”
position = [-0.7, 0.0, -0.09]
Ct = 0.1
Cm = 0.005

Hi @yvescharles,

The geometry file does not take into account shapeshifting like titltrotors or moving CG yet, it generates a static mixer.

For hover flight, this is perfectly fine. As for FW flight, you can have a look at the convergence (http://px4.io/portfolio/e-flite-convergence/). It is the closest PX4-supported VTOL to your design.

Your .toml is almost correct as far as I can tell, except:

  • the z coordinates of the rotors are inverted. I assume the lateral rotors are above CG (z<0) and the frontal one below CG (z>0)
  • the x coordinate of the front thruster is inverted (x>0 in front)
  • to get a 1/10 thrust ratio, the Ct of the front thruster should be 1/10 of the Ct of the other thrusters, ie. 0.05. Unless you meant 1/10th of one contra setup?

I hope it helps!

Hi @jlecoeur
Thanks for the answer.
you’re absolutely right on the toml coordinates and ratio mistakes !
well done !

As I consider tri conf prior to penta, the Ct ratio between C/R"unity" to turbine is 1/10. But it become 1/5 in penta conf (as I realise it’s better to integrate the 2 directions of C/R in the model).

Also, I understand the Ct/Cm should be constant to 1/20, I find a other bug in the turbine Cm… as you can see below

should we ad a VTOL Tiltror MAVTYPE 22 and param set VT_TYPE =3 ?

I’ll try and come back to you asap

Penta Avioneo eVTOL duo coax C/R on dif tiltwings + light1/10 front pitch turbine

[info]
key = “5A”
description = “Penta Avioneo eVTOL duo coax C/R on dif tiltwings + light1/10 front pitch turbine”

[rotor_default]
axis = [0.0, 0.0, -1.0]
Ct = 0.5
Cm = 0.025
direction = “CCW”

[[rotors]]
name = “1-rear_righ_top”
position = [-0.02, 0.975, -0.2]

[[rotors]]
name = “2-rear_right_bot”
position = [-0.02, 0.975, -0.165]
direction = “CW”

[[rotors]]
name = “3-rear_left_up”
position = [-0.02, -0.975, -0.2]

[[rotors]]
name = “4-rear_left_bot”
position = [-0.02, -0.975, -0.165]
direction = “CW”

[[rotors]]
name = “5-front”
position = [0.7, 0.0, 0.09]
Ct = 0.05
Cm = 0.0025

#!nsh

@name Penta Avioneo eVTOL duo coax C/R on dif tiltwings + light1/10 front pitch turbine

@type VTOL Penta Tilt Wings# @class VTOL

@output MAIN1 motors right top

@output MAIN2 motors right bottom

@output MAIN3 motors left top

@output MAIN4 motors left bottom

@output MAIN5 front turbine

@output AUX1 Tilt servo

@output AUX2 Elevon right

@output AUX3 Elevon left

@output AUX4 Foil elevator

@maintainer Yves CHARLES yc@avioneo.com

sh /etc/init.d/rc.vtol_defaults

if [ $AUTOCNF == yes ]
then
param set VT_IDLE_PWM_MC 1150
param set VT_ELEV_MC_LOCK 0
param set VT_MOT_COUNT 5
param set VT_TYPE 1
fi

set MIXER vtol_avioneo2

set PWM_OUT 12345

set MAV_TYPE 21

Compass Sensor 0 missing
Seem a successful run on docker (see output below)
Any Idea ? drivers ?s
Thx

user@98a0c63672e0:/src/firmware$ make distclean
Cleared directory ‘Tools/jMAVSim’
Submodule ‘Tools/jMAVSim’ (GitHub - PX4/jMAVSim: Simple multirotor simulator with MAVLink protocol support) unregistered for path ‘Tools/jMAVSim’
Cleared directory ‘Tools/sitl_gazebo’
Submodule ‘Tools/sitl_gazebo’ (GitHub - PX4/PX4-SITL_gazebo: Set of plugins, models and worlds to use with OSRF Gazebo Simulator in SITL and HITL.) unregistered for path ‘Tools/sitl_gazebo’
Cleared directory ‘cmake/cmake_hexagon’
Cleared directory ‘cmake/configs/uavcan_board_ident’
Cleared directory ‘mavlink/include/mavlink/v2.0’
Submodule ‘mavlink/include/mavlink/v2.0’ (GitHub - mavlink/c_library_v2: Official reference C / C++ library for the v2 protocol) unregistered for path ‘mavlink/include/mavlink/v2.0’
Cleared directory ‘msg/tools/gencpp’
Submodule ‘msg/tools/gencpp’ (GitHub - ros/gencpp: ROS C++ message definition and serialization generators) unregistered for path ‘msg/tools/gencpp’
Cleared directory ‘msg/tools/genmsg’
Submodule ‘msg/tools/genmsg’ (GitHub - ros/genmsg: Standalone Python library for generating ROS message and service data structures for various languages) unregistered for path ‘msg/tools/genmsg’
Cleared directory ‘platforms/nuttx/NuttX/apps’
Submodule ‘platforms/nuttx/NuttX/apps’ (GitHub - PX4/NuttX-apps: Standard NuttX apps with current PX4 patches) unregistered for path ‘platforms/nuttx/NuttX/apps’
Cleared directory ‘platforms/nuttx/NuttX/nuttx’
Submodule ‘platforms/nuttx/NuttX/nuttx’ (GitHub - PX4/NuttX: Standard NuttX with current PX4 patches) unregistered for path ‘platforms/nuttx/NuttX/nuttx’
Cleared directory ‘src/drivers/gps/devices’
Submodule ‘src/drivers/gps/devices’ (GitHub - PX4/PX4-GPSDrivers: Platform independent GPS drivers) unregistered for path ‘src/drivers/gps/devices’
Cleared directory ‘src/lib/DriverFramework’
Submodule ‘src/lib/DriverFramework’ (GitHub - PX4/DriverFramework: Operating system and flight stack agnostic driver framework for POSIX (Linux, NuttX, Mac OS, QNX, VxWorks).) unregistered for path ‘src/lib/DriverFramework’
Cleared directory ‘src/lib/ecl’
Submodule ‘src/lib/ecl’ (GitHub - PX4/PX4-ECL: Estimation & Control Library for Guidance, Navigation and Control Applications) unregistered for path ‘src/lib/ecl’
Cleared directory ‘src/lib/matrix’
Submodule ‘src/lib/matrix’ (GitHub - PX4/PX4-Matrix: Lightweight, dependency free Matrix library (BSD)) unregistered for path ‘src/lib/matrix’
Cleared directory ‘src/modules/micrortps_bridge/micro-CDR’
Cleared directory ‘src/modules/uavcan/libuavcan’
Submodule ‘src/modules/uavcan/libuavcan’ (GitHub - OpenCyphal-Garage/libuavcan: Portable reference implementation of the Cyphal protocol stack in C++ for embedded systems and Linux.) unregistered for path ‘src/modules/uavcan/libuavcan’
Removing Tools/px4airframes/init.pyc
Removing Tools/px4airframes/markdownout.pyc
Removing Tools/px4airframes/rcout.pyc
Removing Tools/px4airframes/srcparser.pyc
Removing Tools/px4airframes/srcscanner.pyc
Removing Tools/px4airframes/xmlout.pyc
Removing build/
Removing msg/tools/px_generate_uorb_topic_helper.pyc
Removing posix-configs/SITL/init/test/cmd_hello_generated
Removing posix-configs/SITL/init/test/cmd_hrt_test_generated
Removing posix-configs/SITL/init/test/cmd_vcdev_test_generated
Removing posix-configs/SITL/init/test/cmd_wqueue_test_generated
Removing posix-configs/SITL/init/test/test_autodeclination_generated
Removing posix-configs/SITL/init/test/test_bson_generated
Removing posix-configs/SITL/init/test/test_commander_generated
Removing posix-configs/SITL/init/test/test_controllib_generated
Removing posix-configs/SITL/init/test/test_conv_generated
Removing posix-configs/SITL/init/test/test_ctlmath_generated
Removing posix-configs/SITL/init/test/test_dataman_generated
Removing posix-configs/SITL/init/test/test_file2_generated
Removing posix-configs/SITL/init/test/test_float_generated
Removing posix-configs/SITL/init/test/test_gpio_generated
Removing posix-configs/SITL/init/test/test_hrt_generated
Removing posix-configs/SITL/init/test/test_hysteresis_generated
Removing posix-configs/SITL/init/test/test_int_generated
Removing posix-configs/SITL/init/test/test_mathlib_generated
Removing posix-configs/SITL/init/test/test_matrix_generated
Removing posix-configs/SITL/init/test/test_microbench_hrt_generated
Removing posix-configs/SITL/init/test/test_microbench_math_generated
Removing posix-configs/SITL/init/test/test_microbench_matrix_generated
Removing posix-configs/SITL/init/test/test_microbench_uorb_generated
Removing posix-configs/SITL/init/test/test_mixer_generated
Removing posix-configs/SITL/init/test/test_param_generated
Removing posix-configs/SITL/init/test/test_parameters_generated
Removing posix-configs/SITL/init/test/test_perf_generated
Removing posix-configs/SITL/init/test/test_rc_generated
Removing posix-configs/SITL/init/test/test_servo_generated
Removing posix-configs/SITL/init/test/test_sf0x_generated
Removing posix-configs/SITL/init/test/test_sleep_generated
Removing posix-configs/SITL/init/test/test_uorb_generated
Removing posix-configs/SITL/init/test/test_versioning_generated
Removing src/lib/parameters/px4params/init.pyc
Removing src/lib/parameters/px4params/markdownout.pyc
Removing src/lib/parameters/px4params/srcparser.pyc
Removing src/lib/parameters/px4params/srcscanner.pyc
Removing src/lib/parameters/px4params/xmlout.pyc
user@98a0c63672e0:/src/firmware$ make clean
user@98a0c63672e0:/src/firmware$ make airframe_metadata
– PX4 config file: /src/firmware/boards/px4/sitl/default.cmake
– PX4 config: px4_sitl_default
– PX4 platform: posix
– PX4 version: v1.8.0-1824-g6b91be9
– cmake build type: RelWithDebInfo
– The CXX compiler identification is GNU 5.4.0
– The C compiler identification is GNU 5.4.0
– The ASM compiler identification is GNU
– Found assembler: /usr/lib/ccache/cc
– Check for working CXX compiler using: Ninja
– Check for working CXX compiler using: Ninja – works
– Detecting CXX compiler ABI info
– Detecting CXX compiler ABI info - done
– Detecting CXX compile features
– Detecting CXX compile features - done
– Check for working C compiler using: Ninja
– Check for working C compiler using: Ninja – works
– Detecting C compiler ABI info
– Detecting C compiler ABI info - done
– Detecting C compile features
– Detecting C compile features - done
– ccache enabled via symlink (/usr/lib/ccache/c++ → /usr/bin/ccache)
– Found PythonInterp: /usr/bin/python (found version “2.7.12”)
– Found PY_jinja2: /usr/local/lib/python2.7/dist-packages/jinja2
– PX4 ECL: Very lightweight Estimation & Control Library v0.9.0-608-gacde4eb
– Configuring done
– Generating done
– Build files have been written to: /src/firmware/build/px4_sitl_default
ninja: Entering directory /src/firmware/build/px4_sitl_default' [1/1] Generating full airframe metadata (markdown and xml) Scanning source path /src/firmware/ROMFS/px4fmu_common/init.d Creating markdown file /src/firmware/build/px4_sitl_default/docs/airframes.md All done! Scanning source path /src/firmware/ROMFS/px4fmu_common/init.d Creating XML file /src/firmware/build/px4_sitl_default/docs/airframes.xml All done! user@98a0c63672e0:/src/firmware$ make px4fmu-v3_default Makefile:194: px4fmu-v3_default has been deprecated and will be removed, please use px4_fmu-v3_default! make px4_fmu-v3_default make[1]: Entering directory '/src/firmware' -- PX4 config file: /src/firmware/boards/px4/fmu-v3/default.cmake -- PX4 config: px4_fmu-v3_default -- PX4 platform: nuttx -- PX4 version: v1.8.0-1824-g6b91be9 -- cmake build type: MinSizeRel -- The CXX compiler identification is GNU 5.4.1 -- The C compiler identification is GNU 5.4.1 -- The ASM compiler identification is GNU -- Found assembler: /opt/gcc/bin/arm-none-eabi-gcc -- Check for working CXX compiler using: Ninja -- Check for working CXX compiler using: Ninja -- works -- Detecting CXX compiler ABI info -- Detecting CXX compiler ABI info - done -- Detecting CXX compile features -- Detecting CXX compile features - done -- Check for working C compiler using: Ninja -- Check for working C compiler using: Ninja -- works -- Detecting C compiler ABI info -- Detecting C compiler ABI info - done -- Detecting C compile features -- Detecting C compile features - done -- ccache enabled (export CCACHE_DISABLE=1 to disable) -- Found PythonInterp: /usr/bin/python (found version "2.7.12") -- Found PY_jinja2: /usr/local/lib/python2.7/dist-packages/jinja2 -- PX4 ECL: Very lightweight Estimation & Control Library v0.9.0-608-gacde4eb -- Building and including px4_io-v2_default -- Using C++11 -- Release build type: MinSizeRel -- Adding UAVCAN STM32 platform driver -- ROMFS: px4fmu_common -- Configuring done -- Generating done -- Build files have been written to: /src/firmware/build/px4_fmu-v3_default ninja: Entering directory /src/firmware/build/px4_fmu-v3_default’
[15/1118] git submodule platforms/nuttx/NuttX/nuttx
[16/1118] git submodule src/lib/ecl
[17/1118] git submodule src/drivers/gps/devices
[18/1118] git submodule mavlink/include/mavlink/v2.0
[19/1118] git submodule src/modules/uavcan/libuavcan
[20/1118] git submodule platforms/nuttx/NuttX/apps
[31/1118] Performing configure step for ‘px4io_firmware’
– PX4 config file: /src/firmware/boards/px4/io-v2/default.cmake
– PX4 config: px4_io-v2_default
– PX4 platform: nuttx
– PX4 version: v1.8.0-1824-g6b91be9
– cmake build type: MinSizeRel
– The CXX compiler identification is GNU 5.4.1
– The C compiler identification is GNU 5.4.1
– The ASM compiler identification is GNU
– Found assembler: /opt/gcc/bin/arm-none-eabi-gcc
– Check for working CXX compiler using: Ninja
– Check for working CXX compiler using: Ninja – works
– Detecting CXX compiler ABI info
– Detecting CXX compiler ABI info - done
– Detecting CXX compile features
– Detecting CXX compile features - done
– Check for working C compiler using: Ninja
– Check for working C compiler using: Ninja – works
– Detecting C compiler ABI info
– Detecting C compiler ABI info - done
– Detecting C compile features
– Detecting C compile features - done
– ccache enabled (export CCACHE_DISABLE=1 to disable)
– Found PythonInterp: /usr/bin/python (found version “2.7.12”)
– Found PY_jinja2: /usr/local/lib/python2.7/dist-packages/jinja2
– PX4 ECL: Very lightweight Estimation & Control Library v0.9.0-608-gacde4eb
– Configuring done
– Generating done
– Build files have been written to: /src/firmware/build/px4_fmu-v3_default/external/Build/px4io_firmware
[32/1118] Performing build step for ‘px4io_firmware’
[8/206] git submodule platforms/nuttx/NuttX/nuttx
[9/206] git submodule platforms/nuttx/NuttX/apps
[206/206] Creating /src/firmware/build/px4_fmu-v3_default/external/Build/px4io_firmware/px4_io-v2_default.px4
[1118/1118] Creating /src/firmware/build/px4_fmu-v3_default/px4_fmu-v3_default.px4
make[1]: Leaving directory ‘/src/firmware’

understand I’ve to use latest docker container, so I now trying direct the easy way with docker_run.sh helper script… will tell you

Compass Sensor 0 still missing after multiples successfull build run

is anyone can help ? @jlecoeur @LorenzMeier

MacBook-Air-de-Yves:Firmware yv$ sudo ./Tools/docker_run.sh “make clean”
Password:
guessing PX4_DOCKER_REPO based on input
PX4_DOCKER_REPO: px4io/px4-dev-nuttx:2018-11-22
Starting with UID : 0
chown: changing ownership of ‘/Users/yv/.ccache’: Operation not permitted
ccache permission issues, disabling
MacBook-Air-de-Yves:Firmware yv$ sudo ./Tools/docker_run.sh “make px4_fmu-v3_default”
Password:
guessing PX4_DOCKER_REPO based on input
PX4_DOCKER_REPO: px4io/px4-dev-nuttx:2018-11-22
Starting with UID : 0
chown: changing ownership of ‘/Users/yv/.ccache’: Operation not permitted
ccache permission issues, disabling
– PX4 config file: /Users/yv/Docker/Px4/src/Firmware/boards/px4/fmu-v3/default.cmake
– PX4 config: px4_fmu-v3_default
– PX4 platform: nuttx
– PX4 version: v1.8.0-1836-gdd9469c1fc
– cmake build type: MinSizeRel
– The CXX compiler identification is GNU 7.2.1
– The C compiler identification is GNU 7.2.1
– The ASM compiler identification is GNU
– Found assembler: /usr/lib/ccache/arm-none-eabi-gcc
– Check for working CXX compiler: /usr/lib/ccache/arm-none-eabi-g++
– Check for working CXX compiler: /usr/lib/ccache/arm-none-eabi-g++ – works
– Detecting CXX compiler ABI info
– Detecting CXX compiler ABI info - done
– Detecting CXX compile features
– Detecting CXX compile features - done
– Check for working C compiler: /usr/lib/ccache/arm-none-eabi-gcc
– Check for working C compiler: /usr/lib/ccache/arm-none-eabi-gcc – works
– Detecting C compiler ABI info
– Detecting C compiler ABI info - done
– Detecting C compile features
– Detecting C compile features - done
– Found PythonInterp: /usr/bin/python (found version “2.7.15”)
– Found PY_jinja2: /usr/local/lib/python2.7/dist-packages/jinja2
– PX4 ECL: Very lightweight Estimation & Control Library v0.9.0-608-gacde4eb
– Building and including px4_io-v2_default
– Using C++11
– Release build type: MinSizeRel
– Adding UAVCAN STM32 platform driver
– ROMFS: px4fmu_common
– Configuring done
– Generating done
– Build files have been written to: /Users/yv/Docker/Px4/src/Firmware/build/px4_fmu-v3_default
ninja: Entering directory `/Users/yv/Docker/Px4/src/Firmware/build/px4_fmu-v3_default’
[10/1118] git submodule platforms/nuttx/NuttX/nuttx
[11/1118] git submodule src/lib/ecl
[13/1118] git submodule src/drivers/gps/devices
[15/1118] git submodule mavlink/include/mavlink/v2.0
[16/1118] git submodule src/modules/uavcan/libuavcan
[18/1118] git submodule platforms/nuttx/NuttX/apps
[276/1118] Performing configure step for ‘px4io_firmware’
– PX4 config file: /Users/yv/Docker/Px4/src/Firmware/boards/px4/io-v2/default.cmake
– PX4 config: px4_io-v2_default
– PX4 platform: nuttx
– PX4 version: v1.8.0-1836-gdd9469c1fc
– cmake build type: MinSizeRel
– The CXX compiler identification is GNU 7.2.1
– The C compiler identification is GNU 7.2.1
– The ASM compiler identification is GNU
– Found assembler: /usr/lib/ccache/arm-none-eabi-gcc
– Check for working CXX compiler: /usr/lib/ccache/arm-none-eabi-g++
– Check for working CXX compiler: /usr/lib/ccache/arm-none-eabi-g++ – works
– Detecting CXX compiler ABI info
– Detecting CXX compiler ABI info - done
– Detecting CXX compile features
– Detecting CXX compile features - done
– Check for working C compiler: /usr/lib/ccache/arm-none-eabi-gcc
– Check for working C compiler: /usr/lib/ccache/arm-none-eabi-gcc – works
– Detecting C compiler ABI info
– Detecting C compiler ABI info - done
– Detecting C compile features
– Detecting C compile features - done
– Found PythonInterp: /usr/bin/python (found version “2.7.15”)
– Found PY_jinja2: /usr/local/lib/python2.7/dist-packages/jinja2
– PX4 ECL: Very lightweight Estimation & Control Library v0.9.0-608-gacde4eb
– Configuring done
– Generating done
– Build files have been written to: /Users/yv/Docker/Px4/src/Firmware/build/px4_fmu-v3_default/external/Build/px4io_firmware
[276/1118] Performing build step for ‘px4io_firmware’
[1/206] git submodule platforms/nuttx/NuttX/nuttx
[3/206] git submodule platforms/nuttx/NuttX/apps
[206/206] Creating /Users/yv/Docker/Px4/src/Firmware/build/px4_fmu-v3_default/external/Build/px4io_firmware/px4_io-v2_default.px4
[1118/1118] Creating /Users/yv/Docker/Px4/src/Firmware/build/px4_fmu-v3_default/px4_fmu-v3_default.px4
MacBook-Air-de-Yves:Firmware yv$

Not a solution though but maybe disabling it will be a temporal workaround?

param set CAL_MAG0_EN 0

@a6a3uh Thanks it’s ok now, see https://github.com/PX4/Firmware/issues/10953

Hi @jlecoeur,

You a re saying that “Ct is in Newton/command, it is the thrust at command 1 (max command).” but for a quad x configuration (https://github.com/PX4/Firmware/blob/master/src/lib/mixer/MultirotorMixer/geometries/quad_x.toml) Ct is equal to 1. Does that mean that the maximum thrust of a motor for this configuration is then 1 Newton ? Because it seems not enough to even hover a drone to me. Is there something I am not understanding well ?

Hi @jlecoeur,

When you are saying “The difference is that PX4 mixers do not output angular velocity, but motor command between 0 and 1. This is then converted to a PWM signal.” how is this conversion done ? Is it a linear mapping with 1 corresponding to the PWM_MAX parameter and 0 to PWM_MIN ?

1 Like