Correct orientation for sensor IC for custom flight controller

I am working on custom harware for Ardupilot flight controller. I am consfuse at IMU and compass IC orientation on PCB. need help for finding correct orientation for sensor ic.
which axis for Front = ?, Right= ?, Top = ? for Compass
and axis for Front = ?, Right= ?, Top = ? for Accel+Gyro
What lines shoud be included in hwdef.dat, if there needs to be rotation.

I am Using following sensors
Compass - MMC5983MA - I2C (As Z axis is showing down. Do I need to keep compass ic at back side of PCB)
Accel + Gryro - BMI088 - SPI
Accel + Gryro - ICM20649 - SPI
Accel + Gryro - ICM42688-p - SPI
Axis images from datasheet.

  1. MMC5983MA

  2. BMI088

  3. ICM20649

  4. ICM42688

Reference this page for correct reference frame (positive X is forward, positive Y is right, positive Z is down).

On the Kakute H7 Mini that I’m using right now, pin 1 of the BMI270 is the left/rear pin with respect to the board’s intended orientation. The BMI270 datasheet shows:

{8631D88A-D0B4-4B18-8AEB-48DA816C2C10}

So to get the correct orientation, the hwdef includes:
IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90

Additional references:
https://ardupilot.org/dev/docs/porting.html

hello @Yuri_Rage thanx for your help. I come up with this orientation for Acell and Gyro IC. please give your suggestion. is this ok or placement is wrong.

I am still confuse about compass IC as its z axis is already down facing. How I can place and rotate axis or I dont need to care for z axis in compass IC.

You are agonizing over the least important part of the circuit design. There are orientation definitions in the source code for nearly every permutation at 45 and 90 degree increments. Place them on the board where interference and resonance is least likely. Same for compass (whose z axis matters but can also be adjusted in hwdef).

You may also find this visualization tool helpful:

https://firmware.ardupilot.org/Tools/WebTools/RotationCheck/

@Yuri_Rage thanks for guidance and help.
I have arrange all sensor ic as X axis matach front direction of flight controller.
this is my hwdef.dat file
hwdef.txt (3.8 KB)

I have used this ROTATIONS
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180
IMU Invensensev2 SPI:icm20649 ROTATION_ROLL_180
IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180
COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_ROLL_180

As compass’s Z axis goes UP side I have to add some changes to its driver make Z Down. I have made Z axis negative in all code snippet. at file

I modify it to

    Vector3f field {float((data1[0] << 8) + data1[1]) - zero_offset,
                   float((data1[2] << 8) + data1[3]) - zero_offset,
                   -float((data1[4] << 8) + data1[5]) - zero_offset};

But I got following errors after booting flight controller

[16:02:57.236] Info: ArduCopter V4.4.4_1 (db53a28f)
[16:02:57.236] Info: ChibiOS: 17a50e3a
[16:02:57.236] Info: EagleFC 002F0034 31335116 36303833
[16:02:57.236] Info: RCOut: Initialising
[16:02:57.236] Info: Frame: HEXA/X
[16:02:57.317] Info: Calibrating barometer
[16:02:57.659] Info: Initialising ArduPilot
[16:02:58.928] Info: Barometer 1 calibration complete
[16:02:58.928] Info: Barometer 2 calibration complete
[16:03:00.118] Info: ArduPilot Ready
[16:03:00.118] Info: AHRS: DCM active
[16:03:00.163] Info: RCOut: PWM:1-14
[16:03:02.120] Info: EKF3 IMU0 initialised
[16:03:02.120] Info: EKF3 IMU1 initialised
[16:03:02.120] Info: EKF3 IMU2 initialised
[16:03:02.122] Info: AHRS: EKF3 active
[16:03:03.419] Info: EKF3 IMU1 tilt alignment complete
[16:03:03.419] Info: EKF3 IMU2 tilt alignment complete
[16:03:03.498] Info: EKF3 IMU1 MAG0 initial yaw alignment complete
[16:03:03.498] Info: EKF3 IMU2 MAG0 initial yaw alignment complete
[16:03:03.522] Info: EKF3 IMU0 tilt alignment complete
[16:03:03.605] Info: EKF3 IMU0 MAG0 initial yaw alignment complete
[16:03:23.157] Critical: PreArm: Accels inconsistent
[16:03:23.157] Critical: PreArm: AHRS: EKF3 Roll/Pitch inconsistent by 177 deg
[16:03:54.165] Critical: PreArm: Accels inconsistent
[16:03:54.166] Critical: PreArm: AHRS: EKF3 Roll/Pitch inconsistent by 177 deg
[16:04:25.167] Critical: PreArm: Accels inconsistent
[16:04:25.168] Critical: PreArm: AHRS: EKF3 Roll/Pitch inconsistent by 177 deg