Eigen Revision
Dependencies: mbed LPS25HB_I2C LSM9DS1 PIDcontroller Autopilot_Eigen LoopTicker GPSUBX_UART_Eigen SBUS_without_mainfile MedianFilter Eigen UsaPack solaESKF_Eigen Vector3 CalibrateMagneto FastPWM
global.cpp
- Committer:
- cocorlow
- Date:
- 2021-05-31
- Revision:
- 56:888379912f81
- Child:
- 58:a7947322db87
File content as of revision 56:888379912f81:
#include "global.hpp" // var // communication Serial pc(USBTX, USBRX, 57600); I2C i2c(PB_9,PB_8); // sda, scl UsaPack tail(PG_14, PG_9, 57600); // log - tail SBUS sbus(PD_5, PD_6); // sensor MPU6050 accelgyro; MAG3110 mag_sensor(PB_9,PB_8); // io DigitalIn userButton(USER_BUTTON); DigitalIn locdef1(PG_2); DigitalIn locdef2(PG_3); // control FastPWM servo(PE_9); PID pitchPID(5.0, 0,0, PID_dt); // rad PID pitchratePID(0.5, 0.0, 0.0, PID_dt); // rad/s HAPS_EKF ekf; // EKF class int loop_count = 0; int obs_count = 0; float att_dt = 0.01f; float rc[16]; int16_t ax, ay, az; int16_t gx, gy, gz; MotionSensorDataUnits mdata; float magval[3] = {1.0f, 0.0f, 0.0f}; // position Vector3 rpy(0.0f, 0.0f, 0.0f); // x:roll y:pitch z:yaw Vector3 rpy_g(0.0f, 0.0f, 0.0f); // x:roll y:pitch z:yaw Vector3 acc; Vector3 accref(0.0f, 0.0f, -0.98f); Vector3 mag; Vector3 magref(0.65f, 0.0f, 0.75f); Vector3 dynacc; Vector3 gyro; Vector3 LPacc(0.0f, 0.0f, 0.0f); Vector3 LPmag(0.0f, 0.0f, 0.0f); int out1, out2; float scaledServoOut[1] = {0.0f}; float servoOut[1] = {1500.0f}; float val_thmg = 0.0f; float th_mg = 0.0f; float accnormerr = 0.0f; int calibrationFlag = 0; int pos_tail = 0; // 0:left 1:center 2:right int agoffset[6] = {0, 0, 0, 386, -450, 48}; float magbias[4] = {0.0f, 0.0f, 0.0f, 50.0f}; Vector3 rpy_align(0.0f*M_PI/180.0f, 0.0f*M_PI/180.0f, 0.0f); // eepromのread writeのためのunionを定義 const int eeprom_address = 0xAE; // EEPROMの3つの入力が全て+より const int eeprom_pointeraddress = 0; // UsaPack const int tail_address[3] = {1111, 2222, 3333}; valuePack posValues[3]; float mapfloat(float x, float in_min, float in_max, float out_min, float out_max) { return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; }