• RE: Voxl IO on Voxl2 J19 port

    @xav04 , i discussed with Jacob and we think you should switch to using our latest firmware for VOXL IO board (M0065) and latest px4. We have made a number of fixes / improvements which are not yet in SDK 1.2.0 (will be in 1.3.0).

    I am going to paste below a lot of useful information that can also be found in our docs, but this may be a bit more concentrated:

    latest m0065 firmware

    https://gitlab.com/voxl-public/voxl-sdk/utilities/voxl2-io/-/blob/master/voxl2-io-tools/firmware/modalai_m0065_firmware_v0_2_RC1_f94baad1.bin?ref_type=heads

    latest px4 build

    http://voxl-packages.modalai.com/dists/qrb5165/dev/binary-arm64/voxl-px4_1.14.0-2.0.70-202404161300_arm64.deb

    how to update m0065 firmware

    https://docs.modalai.com/voxl2-io-firmware/#how-to-update-firmware

    how to enable voxl2-io driver in px4

    check /etc/modalai/voxl-px4.conf configuration file

    # if voxl2-io will be used for ESC, set the ESC parameter:
    ESC=VOXL2_IO_PWM_ESC
    
    # if voxl2-io will be used for SBUS RC input, set the RC parameter:
    RC=M0065_SBUS
    

    how to check which uart port that M0065 board is connected to

    J18-> DSP UART 2
    J19-> DSP UART 7

    script that actually starts px4

    (you should not have to change it, just FYI). use /etc/modalai/voxl-px4.conf for configuration

    /usr/bin/voxl-px4-start
    - qshell voxl2_io start (or `-p 2` will use default uart port 2)
    - qshell voxl2_io start -p 7 (uart port 7)
    

    how to test if VOXL2_IO driver is running

    #stop voxl-px4 instance that may be running in the background
    systemctl stop voxl-px4
    

    start voxl-px4 in foreground and grep for messages from VOXL2_IO

    voxl-px4 -d | grep VOXL2_IO
    ESC: VOXL2_IO_PWM_ESC
    INFO  [muorb] SLPI: VOXL2_IO: Driver starting
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_BAUD  : 921600
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC1 : 101
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC2 : 102
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC3 : 103
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC4 : 104
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC5 : 0
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC6 : 0
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC7 : 0
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC8 : 0
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_DIS   : 1000
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_MIN   : 1100
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_MAX   : 2000
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_CMIN  : 1050
    INFO  [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_CMAX  : 2000
    INFO  [muorb] SLPI: VOXL2_IO: 
    INFO  [muorb] SLPI: VOXL2_IO: Opening UART device 2, baud rate 921600
    INFO  [muorb] SLPI: VOXL2_IO: Successfully opened UART device
    INFO  [muorb] SLPI: VOXL2_IO: Detecting M0065 board...
    INFO  [muorb] SLPI: VOXL2_IO: 	VOXL2_IO ID: 0
    INFO  [muorb] SLPI: VOXL2_IO: 	Board Type : 35: ModalAi I/O Expander (M0065)
    INFO  [muorb] SLPI: VOXL2_IO: 	Unique ID  : 0x4304296039364B560671FF36
    INFO  [muorb] SLPI: VOXL2_IO: 	Firmware   : version    2, hash f94baad1
    INFO  [muorb] SLPI: VOXL2_IO: 	Bootloader : version    0, hash 17147346
    INFO  [muorb] SLPI: VOXL2_IO: 	Reply time : 2550us
    INFO  [muorb] SLPI: VOXL2_IO: Driver initialization succeeded
    

    You will see there were new parameters added, you can see their values in the print above:

    #additional pwm output channels supported ( up to 8 )
    INFO [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC5 : 0
    INFO [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC6 : 0
    INFO [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC7 : 0
    INFO [muorb] SLPI: VOXL2_IO: Params: VOXL2_IO_FUNC8 : 0

    VOXL2_IO_DIS : 1000 #pulse in microseconds when not armed
    VOXL2_IO_MIN : 1100 #min pulse in microseconds when armed
    VOXL2_IO_MAX : 2000 #max pulse in microseconds when armed
    VOXL2_IO_CMIN : 1050 #min pulse in microseconds during esc calibration procedure
    VOXL2_IO_CMAX : 2000 #max pulse in microseconds during esc calibration procedure

    Suggested ESC calibration procedure:

    • power on VOXL2 and ESC while the PWM cable is not plugged into VOXL2. Calibration procedure only works before the ESC receives any valid signals
    • start px4 and QGC and verify that the calibration parameters are set to suggested values (min 1050 and max 2000) and regular min and max values are set to min=1100 and max=2000.
    • verify that the voxl2_io driver has started correctly : either qshell voxl2_io status or look at the blue led on M0065 should be blinking which means it is receiving the pwm commands from voxl2_io driver (the disabled commands, since not armed)
    • start the custom esc calibration procedure : qshell voxl2_io calibrate_escs and follow instructions (which are mainly just plug in the motor pwm cable into m0065 within 10 seconds). You can enter this command right in the px4 prompt, if you start px4 using voxl-px4 -d in foreground in interactive mode
    • after the calibration is complete, test to make sure the PWM ranges have been correctly set:
    • using QGC actuator test, set the actuator slider from disabled (lowest position) to 1100 and the motors should spinup and stay on (no jerking)
    • it is encouraged to double check the motor starting point but temporarily lowering the VOXL2_IO_MIN param to 1000 and using actuator test to find the motor starting point, should be around 1060 (the calibration value was 1050). If the motor starting point is very close to 1100, it may not be safe to use this configuration, because if mixer commands 1100 during flight, variations due to temperature of the ESC MCU could cause 1100 command to be interpreted as DISABLED.
    • IMPORTANT: if VOXL2_IO_MIN was temporarily modified to find the motor starting point, revert it back to the desired value of 1100
    • In order to test actuators other than the 4 motors, you can use QGC to configure the actuator function as for normal actuators.

    additional resources

    posted in VOXL 2 IO
  • RE: Drone flipped upside down when switched to manual mode

    @restore , your motor has the following winding configuration : 24N28P , which means it has 28 poles (14 pole pairs). However, in the params you have not updated the number to 14:

    <param name="num_cycles_per_rev"  value="7"/>      <!-- number of pole pairs in the motor. used for converting electrical frequency to mechanical rpm -->
    

    (this is mentioned in the calibration doc here

    So before doing any more testing, i recommend that you:

    • update num_cycles_per_rev from 7 to 14
    • if you have a optical tachometer, you can actually confirm correct rpm reported by ESC (good to do once just for sanity checking)
    • re-run the calibration procedure for the RPM control (and update the resulting a0, a1, a2 params)
    • update min and max rpms in ESC params and PX4
    • i would recommend setting in PX4 the min_rpm slightly above the absolute minimum that the ESC can achieve. You dont want the motor to spin at bare minimum rpm because it will have almost zero thrust and the attitude control can be a bit unstable when propeller is spinning so slowly (propeller will have very low "disk loading" which results in unstable thrust generation at very low rpm).
    • When i say slightly above, lets say your rpm range is 1000-5000rpm, you can also use a thrust test rig to measure thrust vs rpm.. typically thrust = a *rpm^2, so between 1000rpm and 5000rpm you will have about 25x difference in thrust, so if at full thrust you generate 1000g of thrust, at 1000rpm you will only generate 40g of thrust, which is almost nothing for a large vehicle. So in this case, in flight, i would recommend capping the min rpm around 1250-1500 (in PX4 params). you can still leave the ESC params at absolute min, in this example 1000rpm.
    • once again, the reason for not letting the rpms drop to absolute minimum is to avoid instabilities that can sometimes be caused by the motor spinning at very low rpm (low disk loading, also ESC response is a bit slower)
    • for initial testing, you can set kp and ki to zero, for smoother response. The ESC will behave closer to traditional ESC but still have good RPM control and voltage compensation.
    • (recommendation) you may be able to reduce the spinup_power parameter, the default is pretty high, you can see how much current one motor draws during spin-up, usually 1-2 amps is good. It will not hurt to have the higher value, it will have more torque during spinup, but will draw more current. (we can address that later)

    Also, can you please confirm which firmware version you are using on your FPV ESC?

    I am not 100% convinced that the misconfiguration has caused your issue, but lets get those params corrected and if possible, i'd like to see some of your tests results from the low-kv tuning. (which tests did you run and do you have plots available?)

    Thanks!

    posted in VOXL 2
  • RE: Drone flipped upside down when switched to manual mode

    @restore , it looks like your ESC tuning is off (which may or may not have caused your issue). Take a look at the rpm plot right before the crash happened:

    70676ea1-0484-44e6-801d-72dbeb32df61-image.png

    Look how ESC2 actual rpm (blue) is much higher than ESC2 RPM CMd (cyan). For other motors, too, RPM3 (black) is much higher than ESC3 CMD (purple).

    Can you provide more details:

    • what motor / propeller are you using?
    • have you performed the ESC calibration doc
    • it looks like your motor may be low kv, have you checked and tested your ESC according to this doc

    It looks like right during the switchover from gps control to manual, there was a actuator controls wiggle (see plot below). That caused ESC0 command to quickly dip and come back up. ESC0 (red) responded, rpm dipped trying to follow the command, then came back up very quickly, but then something happened (potentially de-sync) which cased the motor to coast down (between 2:50.5 and 2:52 or so and then continuing to 2:52.750 at which point the stall detection on the ESC reacted, stopped the motor and tried to restart it.

    It definitely looks like the ESC did not follow the command, which could be related to tuning. If you can share the motor/prop information and the ESC params that you used i can investigate further.

    55b086b7-dc71-4830-b977-939c5b2a9bd2-image.png

    posted in VOXL 2
  • RE: collision prevention problem

    @rogerli Also, a PX4 flight log would be helpful. But the SDLOG_PROFILE parameter needs to first be set such that vision and avoidance topics are included. Make sure that parameter is set correctly and then provide a log of a flight where you see a problem along with the voxl-logger output with all of the saved camera frames then that can help us debug what is going on.

    posted in Ask your questions right here!
  • RE: VOXL2 flash error

    @Hyunsoo-Kim-0 Can you post a picture of your hardware setup so we can confirm you're flashing the correct image?

    posted in VOXL 2
  • RE: voxl-microdds-agent not publishing all topics

    Ok @K-Stute I am unable to recreate your issue:

    voxl2:~$ ros2 topic echo /fmu/out/vehicle_status
    timestamp: 1714152702737855
    armed_time: 0
    takeoff_time: 0
    arming_state: 1
    latest_arming_reason: 0
    latest_disarming_reason: 0
    nav_state_timestamp: 15311461
    nav_state_user_intention: 0
    nav_state: 0
    failure_detector_status: 0
    hil_state: 0
    vehicle_type: 1
    failsafe: false
    failsafe_and_user_took_over: false
    gcs_connection_lost: true
    gcs_connection_lost_counter: 0
    high_latency_data_link_lost: false
    is_vtol: false
    is_vtol_tailsitter: false
    in_transition_mode: false
    in_transition_to_fw: false
    system_type: 2
    system_id: 1
    component_id: 1
    safety_button_available: true
    safety_off: true
    power_input_valid: true
    usb_connected: false
    open_drone_id_system_present: false
    open_drone_id_system_healthy: false
    parachute_system_present: false
    parachute_system_healthy: false
    avoidance_system_required: false
    avoidance_system_valid: true
    rc_calibration_in_progress: false
    calibration_enabled: false
    pre_flight_checks_pass: false
    ---
    timestamp: 1714152702778985
    armed_time: 0
    takeoff_time: 0
    arming_state: 1
    latest_arming_reason: 0
    latest_disarming_reason: 0
    nav_state_timestamp: 15311461
    nav_state_user_intention: 0
    nav_state: 0
    failure_detector_status: 0
    hil_state: 0
    vehicle_type: 1
    failsafe: false
    failsafe_and_user_took_over: false
    gcs_connection_lost: true
    gcs_connection_lost_counter: 0
    high_latency_data_link_lost: false
    is_vtol: false
    is_vtol_tailsitter: false
    in_transition_mode: false
    in_transition_to_fw: false
    system_type: 2
    system_id: 1
    component_id: 1
    safety_button_available: true
    safety_off: true
    power_input_valid: true
    usb_connected: false
    open_drone_id_system_present: false
    open_drone_id_system_healthy: false
    parachute_system_present: false
    parachute_system_healthy: false
    avoidance_system_required: false
    avoidance_system_valid: true
    rc_calibration_in_progress: false
    calibration_enabled: false
    pre_flight_checks_pass: false
    ---
    

    The steps I did to do this on a 1.2.0 Voxl-suite -->

    1. Enable/start voxl-px4
    2. sudo apt-get install voxl-ros2-foxy
    3. sudo apt-get install voxl-microdds-agent
    4. sudo apt-get install voxl-mpa-to-ros2
    5. Ensure that microdds-agent service has been started: systemctl start voxl-microdds-agent
    6. voxl-configure-mpa-to-ros2
    7. source /opt/ros/foxy/mpa_to_ros2/install/setup.bash
    8. ros2 topic echo /fmu/out/vehicle_status

    I had to wait about a second for vehicle_status to being publishing as well.

    posted in ROS
  • RE: voxl-microdds-agent not publishing all topics

    Nope! Appreciate the info @K-Stute will be back with a solution soon I hope!

    posted in ROS
  • RE: Voxl IO on Voxl2 J19 port

    Hi @xav04 , sorry to hear you are having problems! Can you share the contents of your voxl-px4.conf (/etc/modalai/voxl-px4.conf)? I would like to get a bit more information to understand what your use case is, is it SBUS RC only as in the link you shared?

    I would also recommend double checking that the voxl2-io driver is running in px4, you can either use QGC or run voxl-px4 with daemon mode disabled then run the command qshell voxl2_io status to check (px4-qshell voxl2_io status will not show you the actual status info).

    -Jacob

    posted in VOXL 2 IO
  • RE: collision prevention problem

    @rogerli

    Hey, happy to try and help!

    Unfortunately a lot of what you're describing sounds like typical camera behavior. We've also struggled with lighting conditions in the past and don't have a great fix. What I'd recommend more than anything is using voxl-logger to collect some logs of what you're seeing through the camera stream. This should enable you to look at the output and see if you notice anything funky and share the logs with us so we can do the same.

    Sorry this isn't the greatest of responses, hope this at least helps some. If you can gather some logs of the behavior you're seeing I'd be happy to take a look at them.

    Thanks,
    Thomas

    posted in Ask your questions right here!
  • RE: voxl-microdds-agent not publishing all topics

    Hi @K-Stute - I will try to recreate on my end as I have not come across this issue before. Just to confirm - what SDK are you on? and also what repository were you looking at for the dds_topics.yaml?

    Zach

    posted in ROS