Browse Source

common:Define default BOARD_NUMBER_I2C_BUSES and BOARD_I2C_BUS_CLOCK_INIT

Define the default I2C buss frequncies that are backward compatible
   with the existing code. While allowing it the defaults to be overridden
   by a board config.

   Based on the legacy STM32 code, the I2C buss numbering starts at 1.
   The bus frequency is stored in a 0 based array. If px4_i2cbus_initialize
   returns a valid device, then the _bus-1 will act as the index to the
   busses frequency.

   A board may define BOARD_NUMBER_I2C_BUSES - the number of I2C busses
   it supports* and BOARD_I2C_BUS_CLOCK_INIT to initalize the bus
   clocks for a given busses.

   BOARD_NUMBER_I2C_BUSES - the number of busses including the *highest
                            number bus. If the board has 2 I2C
                            busses I2C1 and I2C3 BOARD_NUMBER_I2C_BUSES
                            would be set to 3

   BOARD_I2C_BUS_CLOCK_INIT - Initalization for the bus frequencies
                              by bus. A call init, with a frequency
                              less then the value used for the
                              Initalization will result in the device
                              not starting becuase the buss runs too
                              fast for it.
sbg
David Sidrane 8 years ago committed by Lorenz Meier
parent
commit
9644f855e3
  1. 27
      src/drivers/boards/common/board_common.h
  2. 2
      src/platforms/posix/include/system_config.h

27
src/drivers/boards/common/board_common.h

@ -84,7 +84,7 @@ @@ -84,7 +84,7 @@
*
* The PX4_xxxx_BUS_FIRST_CS and PX4_xxxxx_BUS_LAST_CS
* #define PX4_SENSORS_BUS_FIRST_CS PX4_SPIDEV_ICM_20689
* #define PX4_SENSORS_BUS_LAST_CS PX4_SPIDEV_BMI055_ACCEL
* #define PX4_SENSORS_BUS_LAST_CS PX4_SPIDEV_BMI055_ACCEL
*
*
*/
@ -93,6 +93,31 @@ @@ -93,6 +93,31 @@
#define PX4_SPI_BUS_ID(bd) (((bd) >> 4) & 0xf)
#define PX4_SPI_DEV_ID(bd) ((bd) & 0xf)
/* I2C PX4 clock configuration
*
* A board may override BOARD_NUMBER_I2C_BUSES and BOARD_I2C_BUS_CLOCK_INIT
* simply by defining the #defines.
*
* If none are provided the default number of I2C busses will be taken from
* the px4 micro hal and the init will be from the legacy values of 100K.
*/
#if !defined(BOARD_NUMBER_I2C_BUSES)
# define BOARD_NUMBER_I2C_BUSES PX4_NUMBER_I2C_BUSES
#endif
#if !defined(BOARD_I2C_BUS_CLOCK_INIT)
# if (BOARD_NUMBER_I2C_BUSES) == 1
# define BOARD_I2C_BUS_CLOCK_INIT {100000}
# elif (BOARD_NUMBER_I2C_BUSES) == 2
# define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000}
# elif (BOARD_NUMBER_I2C_BUSES) == 3
# define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000}
# elif (BOARD_NUMBER_I2C_BUSES) == 4
# define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000}
# else
# error BOARD_NUMBER_I2C_BUSES not supported
# endif
#endif
/* ADC defining tools
* We want to normalize the V5 Sensing to V = (adc_dn) * ADC_V5_V_FULL_SCALE/(2 ^ ADC_BITS) * ADC_V5_SCALE)
*/

2
src/platforms/posix/include/system_config.h

@ -51,7 +51,7 @@ @@ -51,7 +51,7 @@
#define PX4_SIM_BUS_TEST 2
#define PX4_I2C_BUS_EXPANSION 3
#define PX4_I2C_BUS_LED 3
#define PX4_NUMBER_I2C_BUSES 3
#define PX4_I2C_OBDEV_LED 0x55
#define SIM_FORMATED_UUID "000000010000000200000003"

Loading…
Cancel
Save