ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login
    1. Home
    2. MChehadeh
    3. Topics
    M
    • Profile
    • Following 0
    • Followers 0
    • Topics 4
    • Posts 7
    • Best 0
    • Controversial 0
    • Groups 0

    Topics created by MChehadeh

    • M

      VOXL ESC Mini Integration with px4 on pixhawk6x and KakuteH7

      ESCs
      • • • MChehadeh
      2
      0
      Votes
      2
      Posts
      88
      Views

      Alex KushleyevA

      @MChehadeh , the PX4 ESC driver in v1.14.3 should be functional, but outdated. The latest version lives here : https://github.com/modalai/px4-firmware/tree/voxl-dev/src/drivers/actuators/voxl_esc, it would be best if you are able to build that for your board.

      If you want to stick with the current version, please double check:

      uart port that you are using to connect to the ESC. In that version of the ESC driver, you specify the port with -d param when you spawn the task : https://github.com/PX4/PX4-Autopilot/blob/v1.14.3/src/drivers/actuators/modal_io/modal_io.cpp#L237 double check the baud rate that the ESC is running at, you should know it from running the voxl-esc tools, which are working for you.''

      If you switch to the latest version of the ESC driver in PX4, you should have the following debug information that is very helpful to diagnose any issues:

      #run px4 in foreground and grep for VOXL_ESC: voxl-px4 -d | grep VOXL_ESC INFO [muorb] SLPI: VOXL_ESC: Starting VOXL ESC driver INFO [muorb] SLPI: VOXL_ESC: Opening UART ESC device 2, baud rate 2000000 INFO [muorb] SLPI: VOXL_ESC: Successfully opened UART ESC device INFO [muorb] SLPI: VOXL_ESC: Detecting ESCs... INFO [muorb] SLPI: VOXL_ESC: ESC ID : 0 INFO [muorb] SLPI: VOXL_ESC: Board Type : 37: ModalAi 4-in-1 ESC (M0134-1) INFO [muorb] SLPI: VOXL_ESC: Unique ID : 0x203330385246571900480024 INFO [muorb] SLPI: VOXL_ESC: Firmware : version 39, hash eb6fb500 INFO [muorb] SLPI: VOXL_ESC: Bootloader : version 183, hash b4fa2cf8 INFO [muorb] SLPI: VOXL_ESC: Reply time : 1646us INFO [muorb] SLPI: VOXL_ESC: INFO [muorb] SLPI: VOXL_ESC: ESC ID : 1 INFO [muorb] SLPI: VOXL_ESC: Board Type : 37: ModalAi 4-in-1 ESC (M0134-1) INFO [muorb] SLPI: VOXL_ESC: Unique ID : 0x2033303852465719004D004D INFO [muorb] SLPI: VOXL_ESC: Firmware : version 39, hash eb6fb500 INFO [muorb] SLPI: VOXL_ESC: Bootloader : version 183, hash b4fa2cf8 INFO [muorb] SLPI: VOXL_ESC: Reply time : 621us INFO [muorb] SLPI: VOXL_ESC: INFO [muorb] SLPI: VOXL_ESC: ESC ID : 2 INFO [muorb] SLPI: VOXL_ESC: Board Type : 37: ModalAi 4-in-1 ESC (M0134-1) INFO [muorb] SLPI: VOXL_ESC: Unique ID : 0x203330385246571900500042 INFO [muorb] SLPI: VOXL_ESC: Firmware : version 39, hash eb6fb500 INFO [muorb] SLPI: VOXL_ESC: Bootloader : version 183, hash b4fa2cf8 INFO [muorb] SLPI: VOXL_ESC: Reply time : 1120us INFO [muorb] SLPI: VOXL_ESC: INFO [muorb] SLPI: VOXL_ESC: ESC ID : 3 INFO [muorb] SLPI: VOXL_ESC: Board Type : 37: ModalAi 4-in-1 ESC (M0134-1) INFO [muorb] SLPI: VOXL_ESC: Unique ID : 0x2033303852465719004D0050 INFO [muorb] SLPI: VOXL_ESC: Firmware : version 39, hash eb6fb500 INFO [muorb] SLPI: VOXL_ESC: Bootloader : version 183, hash b4fa2cf8 INFO [muorb] SLPI: VOXL_ESC: Reply time : 617us INFO [muorb] SLPI: VOXL_ESC: INFO [muorb] SLPI: VOXL_ESC: Use extened rpm packet : 1 INFO [muorb] SLPI: VOXL_ESC: All ESCs successfully detected

      No Changes are needed on the hardware side.

      If the UART-based communication does not work for you and you want to use traditional PWM-based (1-2ms) output from the STM board, the ESC mini supports PWM input, just make sure to use the latest ESC firmware.

      https://gitlab.com/voxl-public/voxl-sdk/utilities/voxl-esc/-/tree/master/voxl-esc-tools/firmware https://docs.modalai.com/voxl-mini-esc-datasheet/#pwm-inputs--outputs be very careful soldering and using the test points to make sure not to pull the wires to prevent pulling off the board pads this method is not recommended because you will not receive any feedback about ESC state and closed loop RPM control is not used. We use this for bench testing, for example when using a dyno or something like that (which controls the ESC with standard pwm signal) if you wanted to try PWM input, it is easier using M0134 ESC because it has a JST GH connector : https://docs.modalai.com/modal-esc-datasheet/#pwm-inputs--outputs
    • M

      Maximum rate of rpm, current and voltage measurements of VOXL ESCs

      ESCs
      • • • MChehadeh
      2
      0
      Votes
      2
      Posts
      97
      Views

      Alex KushleyevA

      @MChehadeh ,

      If you need the maximum throughput of the ESC feedback data, you should use the uart-to-serial connection to a linux PC, which you have already done. Additionally, the voxl-esc test scripts already provide an option to specify the command rate (--cmd-rate). Please see the checklist below for best performance:

      make sure the ESC baud rate is set to 2Mbit (first make sure your usb-to-serial adapter can support it). here is an example esc param file showing the baud rate set to 2Mbit. It may already be set to 2Mbit for your esc, you can verify using voxl-esc-scan.py some USB to serial adapters may add some delay, sometimes it helps to experiment with a few. Any particular adapter you have in mind for testing? maximum command rate that has been tested is 4000hz, but it has not been tested extensively, i suggest starting with 2000hz. keep in mind that in order to achieve the maximum rate of esc feedback, you should only test / request feedback from one ESC at a time. The voxl-esc-spin.py test script will request feedback from a single ESC if you only spin one motor (using --id 0, for example), and will automatically request feedback from all ESC at 1/4 of the rate if you spin all motors (using --id 255). So if your cmd-rate is set to 2000 and you spin 4 motors, each ESC will send feedback at 500hz, but if you only spin one motor, the ESC that is spinning will send feedback at the cmd-rate. here is an example of the most basic command that will set the cmd-rate to 2000, spin motor for for 5 seconds and plot the results (including rpm, power %, voltage, current). ./voxl-esc-spin.py --id 0 --cmd-rate 2000 --power 10 --timeout 5 --enable-plot 1 please note that M0129 only measures total battery current that is flowing thru it (not individual), and only ID3 has the current sensor, so you need to test ID3 if you want the total current reported (it will print as BOARD CURRENT in your test script). M0134 ESC has individual current sensing for each ESC channel. if you need the data logged to a file, you can use --enable-logging 1 flag, and the ASCII log will be saved to logs folder inside voxl-esc-tools directory, where you are running the test. The log format is a s follows: PACKET_TYPE LINUX_TIMESTAMP_MS ESC_ID ESC_POWER (RESERVED) ACTUAL_RPM VOLTAGE CURRENT ESC_TEMPERATURE ESC_RCVD_COMMAND_COUNTER RESERVED RESERVED RESERVED

      here is what a typical log entry looks like:

      128 1722869479610 3 10 0 980 11.989 0.024 38.500 20 0 0 0 the standard feedback packet type is 128, in this case the ID 3 is sending feedback, it is spun at power 10%, 980RPM, voltage is 11.989, current is 0.024A (no load spin), ESC temperature is 38.5 deg C if you use M0129, there will be additional packets in the log, with just voltage and current please note that if you use the logging option, the timestamp is saved in milliseconds, so if the feedback is coming back at a higher rate than 1khz, you could not tell the timestamps apart. I will fix this.. one more tip, it helps to run the linux PC in performance mode in order to minimize the cpu delays / sleeps. The ESC feedback packets (currently) do not have the timestamp from the ESC itself, so the accuracy / jitter of the timestamp depends on how quickly the PC can wake up and send/receive the data. you can also modify the spin script to save the data in the format you need, but the log file is probably more reliable to make sure no data is missed.

      Regarding PX4, on VOXL2, the ESC driver runs at 800hz (which is the update rate of the flight loop), each ESC sends feedback at 200hz. ESC status is published at that rate, but it may not logged at full rate to px4 log file, i would need to double check. Here is the code reference : https://github.com/modalai/px4-firmware/blob/voxl-dev/src/drivers/actuators/voxl_esc/voxl_esc.cpp#L1342

      I know this is quite a lot of information, please let me know if you need any other clarification.

      Alex

    • M

      RPM PI control structure

      ESCs
      • • • MChehadeh
      4
      0
      Votes
      4
      Posts
      253
      Views

      Alex KushleyevA

      @MChehadeh yeah it is simply 1/1024. Powers of 2 for faster calculations

      Integral is scaled down a lot because it accumulates fast at 10khz update rate

    • M

      Driving M0134 ESC

      ESCs
      • • • MChehadeh
      6
      0
      Votes
      6
      Posts
      291
      Views

      Alex KushleyevA

      @MChehadeh , thank you for being flexible