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

    Maximum I2C Clock Frequency

    Ask your questions right here!
    3
    19
    1096
    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.
    • Morten NissovM
      Morten Nissov
      last edited by

      Hi again,

      If it's of any help, the repo we're developing this on is: https://github.com/ntnu-arl/modalai-px4-firmware/tree/dev/tmag5273

      There isn't really much going on aside from blending a sparkfun library into the ist8310 impl used as a px4 driver template.

      Eric KatzfeyE 1 Reply Last reply Reply Quote 0
      • Eric KatzfeyE
        Eric Katzfey ModalAI Team @Morten Nissov
        last edited by

        @Morten-Nissov Yes, that means the DSP running PX4 crashed

        1 Reply Last reply Reply Quote 0
        • Eric KatzfeyE
          Eric Katzfey ModalAI Team @Morten Nissov
          last edited by

          @Morten-Nissov This line doesn't look good: ScheduleDelayed(1_us); That's too fast

          Morten NissovM 2 Replies Last reply Reply Quote 0
          • Morten NissovM
            Morten Nissov @Eric Katzfey
            last edited by Morten Nissov

            @Eric-Katzfey I saw the shedule delayed call in the driver we used as template (with a different number), do you have a recommendation for what a lower bound should be?

            We intentionally set it very low to gauge whether the I2C communication was limiting our update rate in the 400kHz case, which it was.

            1 Reply Last reply Reply Quote 0
            • Morten NissovM
              Morten Nissov @Eric Katzfey
              last edited by Morten Nissov

              @Eric-Katzfey Hi again,

              The same happens setting ScheduleDelayed to 20ms (even as high as 100ms). So I guess we're never getting to this point in the code before crashing.

              Edit: The driver manages to run

              	if (!strcmp(verb, "start")) {
              		return ThisDriver::module_start(cli, iterator);
              	}
              

              however it never manages to enter void TMAG5273::RunImpl(). It seems like the crash happens at int ret = I2C::init(); in TMAG5273::init(). Using print statements I can see it never manages to execute any line which requires using I2C (e.g. reading a register for probing), which would seem to make sense is I2C never manages to startup.

              Edit2: As per @Alex-Kushleyev message, I can also manage to change the barometer rate to 1MHz and it starts successfully:

              INFO  [muorb] SLPI: qshell gotten: icp101xx start -I -b 5
              INFO  [muorb] SLPI:   arg0 = 'icp101xx'
              
              INFO  [muorb] SLPI:   arg1 = 'start'
              
              INFO  [muorb] SLPI:   arg2 = '-I'
              
              INFO  [muorb] SLPI:   arg3 = '-b'
              
              INFO  [muorb] SLPI:   arg4 = '5'
              
              INFO  [muorb] SLPI: *** I2C Device ID 0xb76329 12018473
              INFO  [muorb] SLPI: icp101xx #0 on I2C bus 5
              INFO  [muorb] SLPI:  address 0x63
              INFO  [muorb] SLPI: 
              
              INFO  [muorb] SLPI: Ok executing command: icp101xx start -I -b 5
              

              As far as I can see there is virtually no difference in how our mag driver and the barometer driver initialize the I2C object. Note, unplugging the magnetometer results in the same crash as before

              INFO  [muorb] SLPI: qshell gotten: tmag5273 start -X -b 1
              INFO  [muorb] SLPI:   arg0 = 'tmag5273'
              
              INFO  [muorb] SLPI:   arg1 = 'start'
              
              INFO  [muorb] SLPI:   arg2 = '-X'
              
              INFO  [muorb] SLPI:   arg3 = '-b'
              
              INFO  [muorb] SLPI:   arg4 = '1'
              
              INFO  [muorb] SLPI: -----------------------here-------------------
              INFO  [muorb] SLPI: -----------------------hi-------------------
              INFO  [muorb] SLPI: -----------------------start-------------------
              INFO  [muorb] SLPI: *** I2C Device ID 0xd3509 865545
              INFO  [muorb] SLPI: -------------------- const
              INFO  [muorb] SLPI: -------------------- init
              INFO  [muorb] SLPI: -------------------- probe
              INFO  [muorb] SLPI: -------------------- isConnected
              INFO  [muorb] SLPI: Too many arming check events (1, 14 > 14). Not reporting all
              INFO  [muorb] SLPI: Preflight Fail: Accel Sensor 0 missing
              INFO  [muorb] SLPI: Preflight Fail: barometer 0 missing
              INFO  [muorb] SLPI: Preflight Fail: ekf2 missing data
              INFO  [muorb] SLPI: Preflight Fail: Gyro Sensor 0 missing
              INFO  [muorb] SLPI: Preflight Fail: Compass Sensor 0 missing
              INFO  [muorb] SLPI: Preflight Fail: Battery unhealthy
              >>> Got an exception from send_request <<<
              >>> Send succeeded after retries <<<
              Sending topic message
              --- msg_id: 1033
              --- topic name: offboard_control_mode
              

              Note, this time there are some print statement I added to check where the crash was happening. As before it doesn't manage to get past int ret = I2C::init();.

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

                @Morten-Nissov,

                I am not sure exactly what the issue is with 1Mbit i2c rate, but i see another way how you can speed up your reads. Currently the code reads each of the 3 axes separately (X, Y and Z) and each axis is using two separate i2c calls to read the value (LSB and MSB). For each single byte read, it actually takes about 3 bytes (time-wise) because the first byte is the slave address, second byte is the address of register to read and 3rd byte is actual value sent by the sensor.

                All the result registers are stored one after another, specifically designed to be read in a single batch : https://github.com/ntnu-arl/modalai-px4-firmware/blob/dev/tmag5273/src/drivers/magnetometer/tmag5273/TI_TMAG5273_registers.hpp#L187 . So you should change your code to make a single read to read all of the result registers, and if you use the current 400khz, you will get at least 3x speedup, at least in the reading part. Then you have to make sure the sensor has completed the conversion, or whatever is steps are needed for the sensor update cycle.

                Alex

                Morten NissovM 1 Reply Last reply Reply Quote 0
                • Morten NissovM
                  Morten Nissov @Alex Kushleyev
                  last edited by

                  @Alex-Kushleyev Sorry if this is a stupid question, for reading more than one byte with the px4 I2C implementation we do this by calling transfer(&cmd, 1, &buffer, num_read); with the appropriate number for num_read, or is there more to do?

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

                    @Morten-Nissov

                    Yes you can read more than 1 byte at a time by setting num_read accordingly and making sure the buffer for holding the incoming data is large enough. You would need to set the read address to the start address where you want to start reading the data array.

                    Then you will need to parse the data out of the returned array into x, y, z axes (and temperature if you are reading that).

                    Morten NissovM 1 Reply Last reply Reply Quote 0
                    • Morten NissovM
                      Morten Nissov @Alex Kushleyev
                      last edited by

                      @Alex-Kushleyev Sorry didn't see the message, but ended up getting the same place. Implemented a read multiple registers which seems to work:

                      void TMAG5273::RegisterReadMultiple(Register reg, uint8_t* buffer, uint8_t bytes)
                      {
                          const uint8_t cmd = static_cast<uint8_t>(reg);
                          transfer(&cmd, 1, buffer, bytes);
                      }
                      

                      This turned out to be significantly faster (~4x I think), so even without 1MHz I think it could be sufficient for us. Thanks for the help!

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

                        @Morten-Nissov , great! You are welcome. Make sure to change that 1us scheduling interval to a more reasonable value 🙂

                        1 Reply Last reply Reply Quote 0
                        • Morten NissovM Morten Nissov referenced this topic on
                        • First post
                          Last post
                        Powered by NodeBB | Contributors