ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login

    Arming VOXL, but motors won't spin up

    Ask your questions right here!
    4
    14
    672
    Loading More Posts
    • Oldest to Newest
    • Newest to Oldest
    • Most Votes
    Reply
    • Reply as topic
    Log in to reply
    This topic has been deleted. Only users with topic management privileges can see it.
    • Matthew WellnerM
      Matthew Wellner
      last edited by

      Hi,

      I have a VOXL 2 with the m0134_6 ESC that @Alex-Kushleyev has been helping me tune for low kV motors. In the process, I updated the ESC to a new firmware that changed the baud rate from 250000 to 200000. I updated the params for the vehicle in QGC, but now I can arm the VOXL 2, but it won't spin the motors at all and there aren't any errors that I can see.

      I can still voxl-esc scan / spin / etc. without any issues.

      Any ideas?

      Screenshot from 2024-01-23 11-43-21.png

      Alex KushleyevA 1 Reply Last reply Reply Quote 0
      • Alex KushleyevA
        Alex Kushleyev ModalAI Team @Matthew Wellner
        last edited by

        @Matthew-Wellner , the baud rate is 2000000 (2Mbit), not 200K, can you please double check your PX4 params?

        Also, some helpful commands:

        px4-listener esc_status
        

        this will print out the esc_status message, which the ESC driver should be sending out

        Also, if you run voxl-px4 in foreground

        systemctl stop voxl-px4
        voxl-px4 -d
        

        then you can open another terminal / adb and run:

        px4-qshell voxl_esc status
        

        this will print status of voxl esc driver and the params (in the window where voxl-px4 -d is running)

        Chase RileyC Matthew WellnerM 3 Replies Last reply Reply Quote 0
        • Chase RileyC
          Chase Riley @Alex Kushleyev
          last edited by

          @Alex-Kushleyev I may be experiencing the same issue. I will tag along here.

          @Eric-Katzfey I responded in our thread about the spectrum error thinking this might be linked to it, but this is very similar to what I am seeing. So it could be a linked to this instead.

          1 Reply Last reply Reply Quote 0
          • Chase RileyC
            Chase Riley @Alex Kushleyev
            last edited by

            @Alex-Kushleyev This is the results I get from running px4-listener esc_status and capturing the results of running px4-qshell voxl_esc status.

            voxl2:/$ px4-listener esc_status
            
            TOPIC: esc_status
             esc_status
                timestamp: 28243762 (0.002512 seconds ago)
                counter: 12602
                esc_count: 4
                esc_connectiontype: 1
                esc_online_flags: 15 (0b1111)
                esc_armed_flags: 15 (0b1111)
            
              esc[0] (esc_report):
                timestamp: 28241456 (0.005087 seconds ago)
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 24.03100
                esc_current: -0.05600
                esc_temperature: 31.00000
                failures: 0
                esc_address: 3
                esc_cmdcount: 56
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[1] (esc_report):
                timestamp: 28242530 (0.004309 seconds ago)
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 24.03000
                esc_current: -0.01600
                esc_temperature: 30.00000
                failures: 0
                esc_address: 2
                esc_cmdcount: 57
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[2] (esc_report):
                timestamp: 28243762 (0.003363 seconds ago)
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 24.03300
                esc_current: -0.05600
                esc_temperature: 30.00000
                failures: 0
                esc_address: 4
                esc_cmdcount: 58
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[3] (esc_report):
                timestamp: 28240673 (0.006735 seconds ago)
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 24.01200
                esc_current: -0.02400
                esc_temperature: 30.00000
                failures: 0
                esc_address: 1
                esc_cmdcount: 55
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[4] (esc_report):
                timestamp: 0
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 0.00000
                esc_current: 0.00000
                esc_temperature: 0.00000
                failures: 0
                esc_address: 0
                esc_cmdcount: 0
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[5] (esc_report):
                timestamp: 0
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 0.00000
                esc_current: 0.00000
                esc_temperature: 0.00000
                failures: 0
                esc_address: 0
                esc_cmdcount: 0
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[6] (esc_report):
                timestamp: 0
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 0.00000
                esc_current: 0.00000
                esc_temperature: 0.00000
                failures: 0
                esc_address: 0
                esc_cmdcount: 0
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
              esc[7] (esc_report):
                timestamp: 0
                esc_errorcount: 0
                esc_rpm: 0
                esc_voltage: 0.00000
                esc_current: 0.00000
                esc_temperature: 0.00000
                failures: 0
                esc_address: 0
                esc_cmdcount: 0
                esc_state: 0
                actuator_function: 0
                esc_power: 0
            
            INFO  [muorb] SLPI: qshell gotten: voxl_esc status
            INFO  [muorb] SLPI:   arg0 = 'voxl_esc'
            
            INFO  [muorb] SLPI:   arg1 = 'status'
            
            INFO  [muorb] SLPI: Max update rate: 0 Hz
            INFO  [muorb] SLPI: Outputs on: no
            INFO  [muorb] SLPI: UART port: 2
            INFO  [muorb] SLPI: UART open: yes
            INFO  [muorb] SLPI: 
            INFO  [muorb] SLPI: Params: VOXL_ESC_CONFIG: 1
            INFO  [muorb] SLPI: Params: VOXL_ESC_BAUD: 2000000
            INFO  [muorb] SLPI: Params: VOXL_ESC_FUNC1: 103
            INFO  [muorb] SLPI: Params: VOXL_ESC_FUNC2: 102
            INFO  [muorb] SLPI: Params: VOXL_ESC_FUNC3: 104
            INFO  [muorb] SLPI: Params: VOXL_ESC_FUNC4: 101
            INFO  [muorb] SLPI: Params: VOXL_ESC_SDIR1: 0
            INFO  [muorb] SLPI: Params: VOXL_ESC_SDIR2: 0
            INFO  [muorb] SLPI: Params: VOXL_ESC_SDIR3: 0
            INFO  [muorb] SLPI: Params: VOXL_ESC_SDIR4: 0
            INFO  [muorb] SLPI: Params: VOXL_ESC_RPM_MIN: 700
            INFO  [muorb] SLPI: Params: VOXL_ESC_RPM_MAX: 8000
            INFO  [muorb] SLPI: 
            INFO  [muorb] SLPI: -- ID: 0
            INFO  [muorb] SLPI:    Motor:           3
            INFO  [muorb] SLPI:    Direction:       1
            INFO  [muorb] SLPI:    State:           0
            INFO  [muorb] SLPI:    Requested:       0 RPM
            INFO  [muorb] SLPI:    Measured:        0 RPM
            INFO  [muorb] SLPI:    Command Counter: 137
            INFO  [muorb] SLPI:    Voltage:         24.010000 VDC
            INFO  [muorb] SLPI: 
            INFO  [muorb] SLPI: -- ID: 1
            INFO  [muorb] SLPI:    Motor:           2
            INFO  [muorb] SLPI:    Direction:       1
            INFO  [muorb] SLPI:    State:           0
            INFO  [muorb] SLPI:    Requested:       0 RPM
            INFO  [muorb] SLPI:    Measured:        0 RPM
            INFO  [muorb] SLPI:    Command Counter: 138
            INFO  [muorb] SLPI:    Voltage:         24.028002 VDC
            INFO  [muorb] SLPI: 
            INFO  [muorb] SLPI: -- ID: 2
            INFO  [muorb] SLPI:    Motor:           4
            INFO  [muorb] SLPI:    Direction:       1
            INFO  [muorb] SLPI:    State:           0
            INFO  [muorb] SLPI:    Requested:       0 RPM
            INFO  [muorb] SLPI:    Measured:        0 RPM
            INFO  [muorb] SLPI:    Command Counter: 139
            INFO  [muorb] SLPI:    Voltage:         24.020000 VDC
            INFO  [muorb] SLPI: 
            INFO  [muorb] SLPI: -- ID: 3
            INFO  [muorb] SLPI:    Motor:           1
            INFO  [muorb] SLPI:    Direction:       1
            INFO  [muorb] SLPI:    State:           0
            INFO  [muorb] SLPI:    Requested:       0 RPM
            INFO  [muorb] SLPI:    Measured:        0 RPM
            INFO  [muorb] SLPI:    Command Counter: 136
            INFO  [muorb] SLPI:    Voltage:         24.010000 VDC
            INFO  [muorb] SLPI: 
            INFO  [muorb] SLPI: voxl_esc: cycle: 44256 events, 37887531us elapsed, 856.10us avg, min 64us max 2164us 318.
            INFO  [muorb] SLPI: voxl_esc: output update interval: 44255 events, 1271.43us avg, min 196us max 50628us 1397
            INFO  [muorb] SLPI: Param prefix: VOXL_ESC
            INFO  [muorb] SLPI: control latency: 44218 events, 60898443us elapsed, 1377.23us avg, min 314us max 3288us 48
            INFO  [muorb] SLPI: Switched to rate_ctrl work queue
            INFO  [muorb] SLPI: Channel Configuration:
            
            INFO  [muorb] SLPI: Channel 0: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 700, max: 8000
            
            INFO  [muorb] SLPI: Channel 1: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 700, max: 8000
            
            INFO  [muorb] SLPI: Channel 2: func: 104, value: 0, failsafe: 0, disarmed: 0, min: 700, max: 8000
            
            INFO  [muorb] SLPI: Channel 3: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 700, max: 8000
            
            INFO  [muorb] SLPI: Ok executing command: voxl_esc status
            
            Alex KushleyevA 1 Reply Last reply Reply Quote 0
            • Alex KushleyevA
              Alex Kushleyev ModalAI Team @Chase Riley
              last edited by

              @Chase-Riley, your output indicates that the ESC driver in PX4 is communicating with the ESC, I do not see any issue with that!

              Chase RileyC 1 Reply Last reply Reply Quote 0
              • Chase RileyC
                Chase Riley @Alex Kushleyev
                last edited by

                @Alex-Kushleyev Not sure what happened but you are correct it is functioning now.

                1 Reply Last reply Reply Quote 0
                • Matthew WellnerM
                  Matthew Wellner @Alex Kushleyev
                  last edited by

                  @Alex-Kushleyev

                  Interesting - px4-listener esc_status gives me "never published".

                  Screenshot from 2024-01-23 15-13-50.png

                  Matthew WellnerM 1 Reply Last reply Reply Quote 0
                  • Matthew WellnerM
                    Matthew Wellner @Matthew Wellner
                    last edited by

                    @Alex-Kushleyev

                    When I run and the motors don't spin up here is what your second set of commands gives me:

                    Screenshot from 2024-01-23 15-19-52.png

                    Matthew WellnerM 1 Reply Last reply Reply Quote 0
                    • Matthew WellnerM
                      Matthew Wellner @Matthew Wellner
                      last edited by

                      @Alex-Kushleyev

                      I also watched as px4 started up and it looks like the process fails to open the port for the ESC (see the red after the voxl_esc start command) -

                      Screenshot from 2024-01-23 15-22-29.png

                      Alex KushleyevA 1 Reply Last reply Reply Quote 0
                      • Alex KushleyevA
                        Alex Kushleyev ModalAI Team @Matthew Wellner
                        last edited by

                        @Matthew-Wellner your ESC baud rate in PX4 params is 200,000 , not 2,000,000 which is most likely the issue.

                        Alex KushleyevA 1 Reply Last reply Reply Quote 0
                        • Alex KushleyevA
                          Alex Kushleyev ModalAI Team @Alex Kushleyev
                          last edited by

                          the failure to open the UART port is most likely due to unsupported baud rate (200,000) instead of desired baud rate (2,000,000)

                          Matthew WellnerM 1 Reply Last reply Reply Quote 0
                          • Matthew WellnerM
                            Matthew Wellner @Alex Kushleyev
                            last edited by

                            @Alex-Kushleyev - Thanks again. You were right and that was all I needed to change. Sorry!

                            Alex KushleyevA 1 Reply Last reply Reply Quote 0
                            • Alex KushleyevA
                              Alex Kushleyev ModalAI Team @Matthew Wellner
                              last edited by

                              @Matthew-Wellner , no worries! I am glad you got that part working.

                              Kiazoa JoaoK 1 Reply Last reply Reply Quote 0
                              • Kiazoa JoaoK
                                Kiazoa Joao @Alex Kushleyev
                                last edited by

                                @Alex-Kushleyev I had a similar issue and this helped a lot. thanks.

                                1 Reply Last reply Reply Quote 0
                                • First post
                                  Last post
                                Powered by NodeBB | Contributors