Skip to content

Commit

Permalink
reelase 1.3.4
Browse files Browse the repository at this point in the history
  • Loading branch information
AndreyBondarev committed May 24, 2021
1 parent 202fbf4 commit 79c758d
Show file tree
Hide file tree
Showing 124 changed files with 3,832 additions and 907 deletions.
4 changes: 2 additions & 2 deletions examples/OpenIMU300RI/IMU/lib/Core/GPS/include/driverGPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -218,8 +218,8 @@ typedef struct {
int lon_deg;
int lon_min;
double lon_min_fraction;
char latSign;
char lonSign;
int8_t latSign;
int8_t lonSign;
} NmeaLatLonSTRUCT;

// delta struct
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenIMU300RI/IMU/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ platform = aceinna_imu
lib_archive = false
board = OpenIMU300
;lib_deps = ../../../openIMU300-lib
lib_deps = OpenIMU300-base-library@~1.1.11
lib_deps = [email protected].13
build_flags =
; -D CLI
-D IMU_ONLY
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenIMU300RI/IMU/src/appVersion.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ limitations under the License.
#ifndef _IMU_APP_VERSION_H
#define _IMU_APP_VERSION_H

#define APP_VERSION_STRING "IMU_J1939 03.01.09"
#define APP_VERSION_STRING "OpenIMU300RI IMU_J1939 03.01.10"


#endif
5 changes: 3 additions & 2 deletions examples/OpenIMU300RI/IMU/src/user/UserConfigurationUart.c
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ BOOL UpdateSystemParameter(uint32_t number, uint64_t data, BOOL fApply)
{
BOOL result = TRUE;
uint64_t *ptr = (uint64_t *)pUserUartConfig;
uint16_t orientOut;

if(number < USER_UART_CRC || number >= USER_UART_MAX_PARAM ){
return FALSE;
Expand Down Expand Up @@ -89,9 +90,9 @@ BOOL UpdateSystemParameter(uint32_t number, uint64_t data, BOOL fApply)
case USER_UART_ORIENTATION:
{
uint64_t tmp = data;
result = platformSetOrientation((uint16_t*)&data, fApply);
result = platformSetOrientation((uint16_t*)&data, &orientOut, fApply);
if(fApply && result == TRUE){
UpdateEcuOrientationSettings((uint16_t)data);
UpdateEcuOrientationSettings(orientOut);
data = tmp;
}
}
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenIMU300RI/INS/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ platform = aceinna_imu
lib_archive = false
board = OpenIMU300
;lib_deps = ../../../openIMU300-lib
lib_deps = OpenIMU300-base-library@~1.1.11
lib_deps = [email protected].13
build_flags =
-D GPS
-D GPS_OVER_CAN
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenIMU300RI/INS/src/appVersion.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ limitations under the License.
#ifndef _IMU_APP_VERSION_H
#define _IMU_APP_VERSION_H

#define APP_VERSION_STRING "INS_J1939 03.01.09"
#define APP_VERSION_STRING "OpenIMU300RI INS_J1939 03.01.10"


#endif
6 changes: 3 additions & 3 deletions examples/OpenIMU300RI/INS/src/user/UserConfigurationUart.c
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ BOOL UpdateSystemParameter(uint32_t number, uint64_t data, BOOL fApply)
{
BOOL result = TRUE;
uint64_t *ptr = (uint64_t *)pUserUartConfig;

uint16_t orientOut;
if(number < USER_UART_CRC || number >= USER_UART_MAX_PARAM ){
return FALSE;
}
Expand Down Expand Up @@ -89,9 +89,9 @@ BOOL UpdateSystemParameter(uint32_t number, uint64_t data, BOOL fApply)
case USER_UART_ORIENTATION:
{
uint64_t tmp = data;
result = platformSetOrientation((uint16_t*)&data, fApply);
result = platformSetOrientation((uint16_t*)&data, &orientOut, fApply);
if(fApply && result == TRUE){
UpdateEcuOrientationSettings((uint16_t)data);
UpdateEcuOrientationSettings(orientOut);
data = tmp;
}
}
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenIMU300RI/VG_AHRS/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ platform = aceinna_imu
lib_archive = false
board = OpenIMU300
;lib_deps = ../../../openIMU300-lib
lib_deps = OpenIMU300-base-library@~1.1.11
lib_deps = [email protected].13
build_flags =
; -D CLI
; Comment next line for VG algorithm
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenIMU300RI/VG_AHRS/src/appVersion.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ limitations under the License.
#ifndef _IMU_APP_VERSION_H
#define _IMU_APP_VERSION_H

#define APP_VERSION_STRING "VG_AHRS_J1939 03.01.09"
#define APP_VERSION_STRING "OpenIMU300RI VG_AHRS_J1939 03.01.10"


#endif
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,10 @@ BOOL UpdateSystemParameter(uint32_t number, uint64_t data, BOOL fApply)
case USER_UART_ORIENTATION:
{
uint64_t tmp = data;
result = platformSetOrientation((uint16_t*)&data, fApply);
uint16_t orientOut;
result = platformSetOrientation((uint16_t*)&data, &orientOut, fApply);
if(fApply && result == TRUE){
UpdateEcuOrientationSettings((uint16_t)data);
UpdateEcuOrientationSettings(orientOut);
data = tmp;
}
}
Expand Down
File renamed without changes.
23 changes: 22 additions & 1 deletion examples/OpenIMU300ZI/IMU/lib/Core/Algorithm/algorithmAPI.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ limitations under the License.
*
* @retval N/A
*****************************************************************************/
void InitializeAlgorithmStruct(uint8_t callingFreq);
void InitializeAlgorithmStruct(uint8_t callingFreq, const enumIMUType imuType);

/******************************************************************************
* @brief Get algorithm status.
Expand Down Expand Up @@ -68,6 +68,22 @@ void enableGpsInAlgorithm(BOOL enable);

BOOL gpsUsedInAlgorithm();

void enableOdoInAlgorithm(BOOL enable);

BOOL odoUsedInAlgorithm();

void enableFreeIntegration(BOOL enable);

BOOL freeIntegrationEnabled();

void enableStationaryLockYaw(BOOL enable);

BOOL stationaryLockYawEnabled();

void enableImuStaticDetect(BOOL enable);

BOOL imuStaticDetectEnabled();

void SetAlgorithmUseDgps(BOOL d);

void updateAlgorithmTimings(int corr, uint32_t tmrVal );
Expand All @@ -77,6 +93,11 @@ uint32_t getAlgorithmTimer();
uint16_t getAlgorithmCounter();
uint16_t getAlgorithmFrequency();
uint32_t getAlgorithmITOW();
BOOL getAlgorithmLinAccelDetectMode();
BOOL getAlgorithmAccelPredictMode();
float getAlgorithmCoefOfReduceQ();
float getAlgorithmAccelSwitchDelay();
float getAlgorithmRateIntegrationTime();


/******************************************************************************
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include "StateIndices.h"

#include "gpsAPI.h" // For gpsDataStruct_t in EKF setter
#include "odoAPI.h"

#include "Indices.h"

Expand Down Expand Up @@ -64,10 +65,23 @@ typedef struct {
real R[9];
real K[NUMBER_OF_EKF_STATES][3];
real stateUpdate[NUMBER_OF_EKF_STATES];
real deltaP_tmp[NUMBER_OF_EKF_STATES][NUMBER_OF_EKF_STATES];

// The following two are used in more than one functions, so they are pre-computed.
real wTrueTimesDtOverTwo[NUM_AXIS];
real turnSwitchMultiplier;

// saved states when pps comes in
real ppsP[NUMBER_OF_EKF_STATES][NUMBER_OF_EKF_STATES];
real phi[NUMBER_OF_EKF_STATES][NUMBER_OF_EKF_STATES];
real dQ[NUMBER_OF_EKF_STATES][NUMBER_OF_EKF_STATES];
real ppsPosition_N[NUM_AXIS];
real ppsVelocity_N[NUM_AXIS];
//real ppsQuaternion[4];
real ppsEulerAngles[NUM_AXIS];
//real ppsRateBias_B[NUM_AXIS];
//real ppsAccelBias_B[NUM_AXIS];
uint32_t ppsITow;
} KalmanFilterStruct;

extern KalmanFilterStruct gKalmanFilter;
Expand Down Expand Up @@ -96,6 +110,13 @@ typedef struct {
* This is valid only when there is gps udpate.
*/
BOOL gpsUpdate; // Indicate if GNSS measurement is updated.

// odometer
BOOL odoUpdate; // indicate if odo measurement is updated
real odoVelocity; // velocity from odo, [m/s]

// 1PPS from GNSS receiver
BOOL ppsDetected;
} EKF_InputDataStruct;

extern EKF_InputDataStruct gEKFInput;
Expand Down Expand Up @@ -148,7 +169,10 @@ void EKF_GetOperationalMode(uint8_t *EKF_OperMode);
void EKF_GetOperationalSwitches(uint8_t *EKF_LinAccelSwitch, uint8_t *EKF_TurnSwitch);

// Setter functions
void EKF_SetInputStruct(double *accels, double *rates, double *mags, gpsDataStruct_t *gps);
void EKF_SetInputStruct(double *accels, double *rates, double *mags,
gpsDataStruct_t *gps, odoDataStruct_t *odo,
BOOL ppsDetected);
void EKF_SetSteeringAngle(real angle, uint16_t states);
void EKF_SetOutputStruct(void);

#endif /* _EKF_ALGORITHM_H_ */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,11 @@ void MotionStatusImu(real *gyro, real *accel, ImuStatsStruct *imuStats, BOOL res
* @param [in] staticDelay A Counter. When static period detected, delay [staticDelay] samples before
* lowering accel error. [staticDelay] is also used to reset initial accel that
* is propagated using gyro to estimate future accel.
* @param [in] rateBias Input angular rate bias, rad/s.
* @param [out] gAccelStats A struct for results storage.
* @retval None.
******************************************************************************/
void EstimateAccelError(real *accel, real *w, real dt, uint32_t staticDelay, ImuStatsStruct *gAccelStats);
void EstimateAccelError(real *accel, real *w, real dt, uint32_t staticDelay, real *rateBias, ImuStatsStruct *imuStats);

/******************************************************************************
* @brief Detect motion according to the difference between measured accel magnitude and 1g.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ float TimingVars_GetTime(void);

void TimingVars_SetTMin(float tMin);
float TimingVars_GetTMin(void);
void TimingVars_dacqFrequency(int freq);

void TimingVars_DisplayTimerVars(signed long timeStep);

Expand Down
50 changes: 34 additions & 16 deletions examples/OpenIMU300ZI/IMU/lib/Core/Algorithm/include/algorithm.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,24 +77,24 @@ typedef struct {
int32_t Declination_Expiration_Time; // [msec]

uint16_t Free_Integration_Cntr; // [count]
//#define LIMIT_MAX_REST_TIME_BEFORE_DROP_TO_AHRS 60000 // 60000 [ msec ] = 60 [ sec ]
//#define LIMIT_DECL_EXPIRATION_TIME 60000 // 60,000 [ counts ] = 10 [ min ]

real accelSwitch;
uint32_t linAccelSwitchDelay;

uint32_t rateIntegrationTime;
InnovationStruct Innov;
} LimitStruct;

/// specifying how the user sets up the device algorithm
struct algoBehavior_BITS { /// bits description
uint16_t freeIntegrate : 1; /// 0
uint16_t useMag : 1; /// 1
uint16_t useGPS : 1; /// 2 - Not used yet
uint16_t stationaryLockYaw : 1; /// 3 - Not used yet
uint16_t restartOnOverRange : 1; /// 4
uint16_t dynamicMotion : 1; /// 5 - Not used
uint16_t rsvd : 10; /// 6:15
struct algoBehavior_BITS { // bits description
uint16_t freeIntegrate : 1; // 0
uint16_t useMag : 1; // 1
uint16_t useGPS : 1; // 2
uint16_t useOdo : 1; // 3
uint16_t enableStationaryLockYaw : 1; // 4
uint16_t restartOnOverRange : 1; // 5
uint16_t dynamicMotion : 1; // 6
uint16_t enableImuStaticDetect : 1; // 7
uint16_t rsvd : 8; // 8:15
};

union AlgoBehavior
Expand All @@ -110,11 +110,21 @@ struct ALGO_STATUS_BITS
uint16_t highGain : 1; // 1 high gain mode
uint16_t attitudeOnlyAlgorithm : 1; // 2 attitude only algorithm
uint16_t turnSwitch : 1; // 3 turn switch
uint16_t noAirdataAiding : 1; // 4 airdata aiding
uint16_t noMagnetometerheading : 1; // 5 magnetometer heading
uint16_t noGPSTrackReference : 1; // 6 GPS track
uint16_t gpsUpdate : 1; // 7 GPS measurement update
uint16_t rsvd : 8; // 8:15
uint16_t linearAccel : 1; // 4 Linear acceleration detected by difference from gravity
uint16_t staticImu : 1; // 5 zero velocity detected by IMU
uint16_t gpsHeadingValid : 1; /* 6 When GPS velocity is above a certain threshold,
* this is set to TRUE, and GPS heading measurement
* is used, otherwise, this is set to FALSE and magnetic
* heading (if available) is used.
*/
uint16_t stationaryYawLock : 1; // 7 Yaw is locked when unit is static
uint16_t ppsAvailable : 1; /* 8.
* This will be initialized as FALSE.
* This will become TRUE when PPS is detected for the first time.
* This will become FALSE when PPS has not been detected for more than 2sec.
* This will become FALSE when GNSS measurement is refrshed and used.
*/
uint16_t rsvd : 7; // 9:15
};

typedef union ALGO_STATUS
Expand Down Expand Up @@ -182,6 +192,8 @@ typedef struct {

uint8_t linAccelLPFType;
uint8_t useRawAccToDetectLinAccel;
uint8_t useRawRateToPredAccel;
real coefOfReduceQ;

uint8_t callingFreq;
real dt;
Expand All @@ -205,8 +217,14 @@ typedef struct {

DurationStruct Duration;
LimitStruct Limit;
enumIMUType imuType;

} AlgorithmStruct;

extern AlgorithmStruct gAlgorithm;

// Update IMU specs.
void UpdateImuSpec(real rwOdr, real arw, real biw, real maxBiasW,
real vrw, real bia, real maxBiasA);

#endif
Loading

0 comments on commit 79c758d

Please sign in to comment.