Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: BMP280 HCSR04_from_mtmt MPU6050_2 mbed SDFileSystem3
Revision 0:2b57931c6ed4, committed 2022-09-13
- Comitter:
- hitonari
- Date:
- Tue Sep 13 03:12:26 2022 +0000
- Child:
- 1:e7079f9771d3
- Commit message:
- test
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/BMP280.lib Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/teams/1519026547/code/BMP280/#315c0737f4bc
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/HCSR04_from_mtmt.lib Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/teams/1519026547/code/HCSR04_from_mtmt/#f077c49e84f6
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MPU6050.lib Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/teams/1519026547/code/MPU6050_2/#e1e51291024e
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU9250_BMP.h Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,884 @@
+#ifndef MPU9250_H
+#define MPU9250_H
+
+#include "mbed.h"
+#include "math.h"
+
+// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in
+// above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map
+//
+//Magnetometer Registers
+#define AK8963_ADDRESS 0x0C<<1
+#define WHO_AM_I_AK8963 0x00 // should return 0x48
+#define INFO 0x01
+#define AK8963_ST1 0x02 // data ready status bit 0
+#define AK8963_XOUT_L 0x03 // data
+#define AK8963_XOUT_H 0x04
+#define AK8963_YOUT_L 0x05
+#define AK8963_YOUT_H 0x06
+#define AK8963_ZOUT_L 0x07
+#define AK8963_ZOUT_H 0x08
+#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2
+#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0
+#define AK8963_ASTC 0x0C // Self test control
+#define AK8963_I2CDIS 0x0F // I2C disable
+#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value
+#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
+#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
+
+#define SELF_TEST_X_GYRO 0x00
+#define SELF_TEST_Y_GYRO 0x01
+#define SELF_TEST_Z_GYRO 0x02
+
+/*#define X_FINE_GAIN 0x03 // [7:0] fine gain
+#define Y_FINE_GAIN 0x04
+#define Z_FINE_GAIN 0x05
+#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer
+#define XA_OFFSET_L_TC 0x07
+#define YA_OFFSET_H 0x08
+#define YA_OFFSET_L_TC 0x09
+#define ZA_OFFSET_H 0x0A
+#define ZA_OFFSET_L_TC 0x0B */
+
+#define SELF_TEST_X_ACCEL 0x0D
+#define SELF_TEST_Y_ACCEL 0x0E
+#define SELF_TEST_Z_ACCEL 0x0F
+
+#define SELF_TEST_A 0x10
+
+#define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope
+#define XG_OFFSET_L 0x14
+#define YG_OFFSET_H 0x15
+#define YG_OFFSET_L 0x16
+#define ZG_OFFSET_H 0x17
+#define ZG_OFFSET_L 0x18
+#define SMPLRT_DIV 0x19
+#define CONFIG 0x1A
+#define GYRO_CONFIG 0x1B
+#define ACCEL_CONFIG 0x1C
+#define ACCEL_CONFIG2 0x1D
+#define LP_ACCEL_ODR 0x1E
+#define WOM_THR 0x1F
+
+#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms
+#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0]
+#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms
+
+#define FIFO_EN 0x23
+#define I2C_MST_CTRL 0x24
+#define I2C_SLV0_ADDR 0x25
+#define I2C_SLV0_REG 0x26
+#define I2C_SLV0_CTRL 0x27
+#define I2C_SLV1_ADDR 0x28
+#define I2C_SLV1_REG 0x29
+#define I2C_SLV1_CTRL 0x2A
+#define I2C_SLV2_ADDR 0x2B
+#define I2C_SLV2_REG 0x2C
+#define I2C_SLV2_CTRL 0x2D
+#define I2C_SLV3_ADDR 0x2E
+#define I2C_SLV3_REG 0x2F
+#define I2C_SLV3_CTRL 0x30
+#define I2C_SLV4_ADDR 0x31
+#define I2C_SLV4_REG 0x32
+#define I2C_SLV4_DO 0x33
+#define I2C_SLV4_CTRL 0x34
+#define I2C_SLV4_DI 0x35
+#define I2C_MST_STATUS 0x36
+#define INT_PIN_CFG 0x37
+#define INT_ENABLE 0x38
+#define DMP_INT_STATUS 0x39 // Check DMP interrupt
+#define INT_STATUS 0x3A
+#define ACCEL_XOUT_H 0x3B
+#define ACCEL_XOUT_L 0x3C
+#define ACCEL_YOUT_H 0x3D
+#define ACCEL_YOUT_L 0x3E
+#define ACCEL_ZOUT_H 0x3F
+#define ACCEL_ZOUT_L 0x40
+#define TEMP_OUT_H 0x41
+#define TEMP_OUT_L 0x42
+#define GYRO_XOUT_H 0x43
+#define GYRO_XOUT_L 0x44
+#define GYRO_YOUT_H 0x45
+#define GYRO_YOUT_L 0x46
+#define GYRO_ZOUT_H 0x47
+#define GYRO_ZOUT_L 0x48
+#define EXT_SENS_DATA_00 0x49
+#define EXT_SENS_DATA_01 0x4A
+#define EXT_SENS_DATA_02 0x4B
+#define EXT_SENS_DATA_03 0x4C
+#define EXT_SENS_DATA_04 0x4D
+#define EXT_SENS_DATA_05 0x4E
+#define EXT_SENS_DATA_06 0x4F
+#define EXT_SENS_DATA_07 0x50
+#define EXT_SENS_DATA_08 0x51
+#define EXT_SENS_DATA_09 0x52
+#define EXT_SENS_DATA_10 0x53
+#define EXT_SENS_DATA_11 0x54
+#define EXT_SENS_DATA_12 0x55
+#define EXT_SENS_DATA_13 0x56
+#define EXT_SENS_DATA_14 0x57
+#define EXT_SENS_DATA_15 0x58
+#define EXT_SENS_DATA_16 0x59
+#define EXT_SENS_DATA_17 0x5A
+#define EXT_SENS_DATA_18 0x5B
+#define EXT_SENS_DATA_19 0x5C
+#define EXT_SENS_DATA_20 0x5D
+#define EXT_SENS_DATA_21 0x5E
+#define EXT_SENS_DATA_22 0x5F
+#define EXT_SENS_DATA_23 0x60
+#define MOT_DETECT_STATUS 0x61
+#define I2C_SLV0_DO 0x63
+#define I2C_SLV1_DO 0x64
+#define I2C_SLV2_DO 0x65
+#define I2C_SLV3_DO 0x66
+#define I2C_MST_DELAY_CTRL 0x67
+#define SIGNAL_PATH_RESET 0x68
+#define MOT_DETECT_CTRL 0x69
+#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP
+#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode
+#define PWR_MGMT_2 0x6C
+#define DMP_BANK 0x6D // Activates a specific bank in the DMP
+#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank
+#define DMP_REG 0x6F // Register in DMP from which to read or to which to write
+#define DMP_REG_1 0x70
+#define DMP_REG_2 0x71
+#define FIFO_COUNTH 0x72
+#define FIFO_COUNTL 0x73
+#define FIFO_R_W 0x74
+#define WHO_AM_I_MPU9250 0x75 // Should return 0x71
+#define XA_OFFSET_H 0x77
+#define XA_OFFSET_L 0x78
+#define YA_OFFSET_H 0x7A
+#define YA_OFFSET_L 0x7B
+#define ZA_OFFSET_H 0x7D
+#define ZA_OFFSET_L 0x7E
+
+// Using the MSENSR-9250 breakout board, ADO is set to 0
+// Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1
+//mbed uses the eight-bit device address, so shift seven-bit addresses left by one!
+#define ADO 0
+#if ADO
+#define MPU9250_ADDRESS 0x69<<1 // Device address when ADO = 1
+#else
+#define MPU9250_ADDRESS 0x68<<1 // Device address when ADO = 0
+#endif
+
+// Set initial input parameters
+enum Ascale {
+ AFS_2G = 0,
+ AFS_4G,
+ AFS_8G,
+ AFS_16G
+};
+
+enum Gscale {
+ GFS_250DPS = 0,
+ GFS_500DPS,
+ GFS_1000DPS,
+ GFS_2000DPS
+};
+
+enum Mscale {
+ MFS_14BITS = 0, // 0.6 mG per LSB
+ MFS_16BITS // 0.15 mG per LSB
+};
+
+uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G
+uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
+uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
+uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR
+float aRes, gRes, mRes; // scale resolutions per LSB for the sensors
+
+//Set up I2C, (SDA,SCL)
+//I2C i2c(I2C_SDA, I2C_SCL);
+I2C i2c(PC_9, PA_8);
+
+DigitalOut myled(LED1);
+
+// Pin definitions
+int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins
+
+int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output
+int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output
+int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output
+float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias
+float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
+float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
+int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius
+float temperature;
+float SelfTest[6];
+
+int delt_t = 0; // used to control display output rate
+int count = 0; // used to control display output rate
+
+// parameters for 6 DoF sensor fusion calculations
+float PI = 3.14159265358979323846f;
+float GyroMeasError = PI * (60.0f / 180.0f); // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3
+float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
+float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
+float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
+#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
+#define Ki 0.0f
+
+float pitch, yaw, roll;
+float deltat = 0.0f; // integration interval for both filter schemes
+int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval
+float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion
+float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
+
+class MPU9250 {
+
+ protected:
+
+ public:
+ //===================================================================================================================
+//====== Set of useful function to access acceleratio, gyroscope, and temperature data
+//===================================================================================================================
+
+ void writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
+{
+ char data_write[2];
+ data_write[0] = subAddress;
+ data_write[1] = data;
+ i2c.write(address, data_write, 2, 0);
+}
+
+ char readByte(uint8_t address, uint8_t subAddress)
+{
+ char data[1]; // `data` will store the register data
+ char data_write[1];
+ data_write[0] = subAddress;
+ i2c.write(address, data_write, 1, 1); // no stop
+ i2c.read(address, data, 1, 0);
+ return data[0];
+}
+
+ void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
+{
+ char data[14];
+ char data_write[1];
+ data_write[0] = subAddress;
+ i2c.write(address, data_write, 1, 1); // no stop
+ i2c.read(address, data, count, 0);
+ for(int ii = 0; ii < count; ii++) {
+ dest[ii] = data[ii];
+ }
+}
+
+
+void getMres() {
+ switch (Mscale)
+ {
+ // Possible magnetometer scales (and their register bit settings) are:
+ // 14 bit resolution (0) and 16 bit resolution (1)
+ case MFS_14BITS:
+ mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss
+ break;
+ case MFS_16BITS:
+ mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss
+ break;
+ }
+}
+
+
+void getGres() {
+ switch (Gscale)
+ {
+ // Possible gyro scales (and their register bit settings) are:
+ // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
+ // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
+ case GFS_250DPS:
+ gRes = 250.0/32768.0;
+ break;
+ case GFS_500DPS:
+ gRes = 500.0/32768.0;
+ break;
+ case GFS_1000DPS:
+ gRes = 1000.0/32768.0;
+ break;
+ case GFS_2000DPS:
+ gRes = 2000.0/32768.0;
+ break;
+ }
+}
+
+
+void getAres() {
+ switch (Ascale)
+ {
+ // Possible accelerometer scales (and their register bit settings) are:
+ // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
+ // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
+ case AFS_2G:
+ aRes = 2.0/32768.0;
+ break;
+ case AFS_4G:
+ aRes = 4.0/32768.0;
+ break;
+ case AFS_8G:
+ aRes = 8.0/32768.0;
+ break;
+ case AFS_16G:
+ aRes = 16.0/32768.0;
+ break;
+ }
+}
+
+
+void readAccelData(int16_t * destination)
+{
+ uint8_t rawData[6]; // x/y/z accel register data stored here
+ //readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
+ readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, rawData);
+
+ destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+ destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+ destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+}
+
+void readGyroData(int16_t * destination)
+{
+ uint8_t rawData[6]; // x/y/z gyro register data stored here
+ //readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
+ readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, rawData);
+ destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+ destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+ destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+}
+
+void readMagData(int16_t * destination)
+{
+ uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
+ if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
+ //readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array
+ readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, rawData);
+ uint8_t c = rawData[6]; // End data read by reading ST2 register
+ if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
+ destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value
+ destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian
+ destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ;
+ }
+ }
+}
+
+int16_t readTempData()
+{
+ uint8_t rawData[2]; // x/y/z gyro register data stored here
+ readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array
+ return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value
+}
+
+
+void resetMPU9250() {
+ // reset device
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
+ wait(0.1);
+ }
+
+ void initAK8963(float * destination)
+{
+ // First extract the factory calibration for each magnetometer axis
+ uint8_t rawData[3]; // x/y/z gyro calibration data stored here
+ writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
+ wait(0.01);
+ writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
+ wait(0.01);
+ readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values
+ destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc.
+ destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f;
+ destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f;
+ writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
+ wait(0.01);
+ // Configure the magnetometer for continuous read and highest resolution
+ // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
+ // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
+ writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
+ wait(0.01);
+}
+
+
+void initMPU9250()
+{
+ // Initialize MPU9250 device
+ // wake up device
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
+ wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
+
+ // get stable time source
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
+
+ // Configure Gyro and Accelerometer
+ // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
+ // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
+ // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
+ writeByte(MPU9250_ADDRESS, CONFIG, 0x03);
+
+ // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
+ writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
+
+ // Set gyroscope full scale range
+ // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
+ uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value
+ // c = c & ~0xE0; // Clear self-test bits [7:5]
+ c = c & ~0x02; // Clear Fchoice bits [1:0]
+ c = c & ~0x18; // Clear AFS bits [4:3]
+ c = c | Gscale << 3; // Set full scale range for the gyro
+ // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG
+ writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register
+
+ // Set accelerometer full-scale range configuration
+ c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value
+ // c = c & ~0xE0; // Clear self-test bits [7:5]
+ c = c & ~0x18; // Clear AFS bits [4:3]
+ c = c | Ascale << 3; // Set full scale range for the accelerometer
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value
+
+ // Set accelerometer sample rate configuration
+ // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
+ // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
+ c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value
+ c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
+ c = c | 0x03; // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value
+
+ // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
+ // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
+
+ // Configure Interrupts and Bypass Enable
+ // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
+ // can join the I2C bus and all can be controlled by the Arduino as master
+ writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22);
+ writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
+}
+
+// Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
+// of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
+void calibrateMPU9250(float * dest1, float * dest2)
+{
+ uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
+ uint16_t ii, packet_count, fifo_count;
+ int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
+
+// reset device, reset all registers, clear gyro and accelerometer bias registers
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
+ wait(0.1);
+
+// get stable time source
+// Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00);
+ wait(0.2);
+
+// Configure device for bias calculation
+ writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
+ writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
+ writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
+ writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
+ writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
+ writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
+ wait(0.015);
+
+// Configure MPU9250 gyro and accelerometer for bias calculation
+ writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
+ writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
+ writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
+
+ uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
+ uint16_t accelsensitivity = 16384; // = 16384 LSB/g
+
+// Configure FIFO to capture accelerometer and gyro data for bias calculation
+ writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
+ writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
+ wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
+
+// At end of sample accumulation, turn off FIFO sensor read
+ writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
+ readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
+ fifo_count = ((uint16_t)data[0] << 8) | data[1];
+ packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
+
+ for (ii = 0; ii < packet_count; ii++) {
+ int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
+ readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
+ accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO
+ accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
+ accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
+ gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ;
+ gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ;
+ gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
+
+ accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
+ accel_bias[1] += (int32_t) accel_temp[1];
+ accel_bias[2] += (int32_t) accel_temp[2];
+ gyro_bias[0] += (int32_t) gyro_temp[0];
+ gyro_bias[1] += (int32_t) gyro_temp[1];
+ gyro_bias[2] += (int32_t) gyro_temp[2];
+
+}
+ accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
+ accel_bias[1] /= (int32_t) packet_count;
+ accel_bias[2] /= (int32_t) packet_count;
+ gyro_bias[0] /= (int32_t) packet_count;
+ gyro_bias[1] /= (int32_t) packet_count;
+ gyro_bias[2] /= (int32_t) packet_count;
+
+ if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation
+ else {accel_bias[2] += (int32_t) accelsensitivity;}
+
+// Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
+ data[0] = (-gyro_bias[0]/4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
+ data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
+ data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF;
+ data[3] = (-gyro_bias[1]/4) & 0xFF;
+ data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF;
+ data[5] = (-gyro_bias[2]/4) & 0xFF;
+
+/// Push gyro biases to hardware registers
+/* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
+ writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
+ writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
+ writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
+ writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
+ writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
+*/
+ dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
+ dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
+ dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
+
+// Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
+// factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
+// non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
+// compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
+// the accelerometer biases calculated above must be divided by 8.
+
+ int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
+ readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
+ accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
+ readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
+ accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
+ readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
+ accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
+
+ uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
+ uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
+
+ for(ii = 0; ii < 3; ii++) {
+ if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
+ }
+
+ // Construct total accelerometer bias, including calculated average accelerometer bias from above
+ accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
+ accel_bias_reg[1] -= (accel_bias[1]/8);
+ accel_bias_reg[2] -= (accel_bias[2]/8);
+
+ data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
+ data[1] = (accel_bias_reg[0]) & 0xFF;
+ data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
+ data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
+ data[3] = (accel_bias_reg[1]) & 0xFF;
+ data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
+ data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
+ data[5] = (accel_bias_reg[2]) & 0xFF;
+ data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
+
+// Apparently this is not working for the acceleration biases in the MPU-9250
+// Are we handling the temperature correction bit properly?
+// Push accelerometer biases to hardware registers
+/* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
+ writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
+ writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
+ writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
+ writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
+ writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
+*/
+// Output scaled accelerometer biases for manual subtraction in the main program
+ dest2[0] = (float)accel_bias[0]/(float)accelsensitivity;
+ dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
+ dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
+}
+
+
+// Accelerometer and gyroscope self test; check calibration wrt factory settings
+void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
+{
+ uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
+ uint8_t selfTest[6];
+ int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3];
+ float factoryTrim[6];
+ uint8_t FS = 0;
+
+ writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
+ writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
+ writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
+
+ for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
+
+ readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
+ aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+ aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+ aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+
+ readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
+ gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+ gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+ gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+ }
+
+ for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
+ aAvg[ii] /= 200;
+ gAvg[ii] /= 200;
+ }
+
+// Configure the accelerometer for self-test
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
+ writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
+ //delay(55); // Delay a while to let the device stabilize
+
+ for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
+
+ readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
+ aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+ aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+ aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+
+ readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
+ gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+ gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+ gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+ }
+
+ for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
+ aSTAvg[ii] /= 200;
+ gSTAvg[ii] /= 200;
+ }
+
+ // Configure the gyro and accelerometer for normal operation
+ writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
+ writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
+ //delay(45); // Delay a while to let the device stabilize
+
+ // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
+ selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
+ selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
+ selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
+ selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
+ selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
+ selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
+
+ // Retrieve factory self-test value from self-test code reads
+ factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation
+ factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation
+ factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation
+ factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation
+ factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation
+ factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation
+
+ // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
+ // To get percent, must multiply by 100
+ for (int i = 0; i < 3; i++) {
+ destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences
+ destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences
+ }
+
+}
+
+
+
+// Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
+// (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
+// which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
+// device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
+// The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
+// but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
+ void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
+ {
+ float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
+ float norm;
+ float hx, hy, _2bx, _2bz;
+ float s1, s2, s3, s4;
+ float qDot1, qDot2, qDot3, qDot4;
+
+ // Auxiliary variables to avoid repeated arithmetic
+ float _2q1mx;
+ float _2q1my;
+ float _2q1mz;
+ float _2q2mx;
+ float _4bx;
+ float _4bz;
+ float _2q1 = 2.0f * q1;
+ float _2q2 = 2.0f * q2;
+ float _2q3 = 2.0f * q3;
+ float _2q4 = 2.0f * q4;
+ float _2q1q3 = 2.0f * q1 * q3;
+ float _2q3q4 = 2.0f * q3 * q4;
+ float q1q1 = q1 * q1;
+ float q1q2 = q1 * q2;
+ float q1q3 = q1 * q3;
+ float q1q4 = q1 * q4;
+ float q2q2 = q2 * q2;
+ float q2q3 = q2 * q3;
+ float q2q4 = q2 * q4;
+ float q3q3 = q3 * q3;
+ float q3q4 = q3 * q4;
+ float q4q4 = q4 * q4;
+
+ // Normalise accelerometer measurement
+ norm = sqrt(ax * ax + ay * ay + az * az);
+ if (norm == 0.0f) return; // handle NaN
+ norm = 1.0f/norm;
+ ax *= norm;
+ ay *= norm;
+ az *= norm;
+
+ // Normalise magnetometer measurement
+ norm = sqrt(mx * mx + my * my + mz * mz);
+ if (norm == 0.0f) return; // handle NaN
+ norm = 1.0f/norm;
+ mx *= norm;
+ my *= norm;
+ mz *= norm;
+
+ // Reference direction of Earth's magnetic field
+ _2q1mx = 2.0f * q1 * mx;
+ _2q1my = 2.0f * q1 * my;
+ _2q1mz = 2.0f * q1 * mz;
+ _2q2mx = 2.0f * q2 * mx;
+ hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
+ hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
+ _2bx = sqrt(hx * hx + hy * hy);
+ _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
+ _4bx = 2.0f * _2bx;
+ _4bz = 2.0f * _2bz;
+
+ // Gradient decent algorithm corrective step
+ s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
+ s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
+ s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
+ s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
+ norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
+ norm = 1.0f/norm;
+ s1 *= norm;
+ s2 *= norm;
+ s3 *= norm;
+ s4 *= norm;
+
+ // Compute rate of change of quaternion
+ qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
+ qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
+ qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
+ qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
+
+ // Integrate to yield quaternion
+ q1 += qDot1 * deltat;
+ q2 += qDot2 * deltat;
+ q3 += qDot3 * deltat;
+ q4 += qDot4 * deltat;
+ norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
+ norm = 1.0f/norm;
+ q[0] = q1 * norm;
+ q[1] = q2 * norm;
+ q[2] = q3 * norm;
+ q[3] = q4 * norm;
+
+ }
+
+
+
+ // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
+ // measured ones.
+ void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
+ {
+ float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
+ float norm;
+ float hx, hy, bx, bz;
+ float vx, vy, vz, wx, wy, wz;
+ float ex, ey, ez;
+ float pa, pb, pc;
+
+ // Auxiliary variables to avoid repeated arithmetic
+ float q1q1 = q1 * q1;
+ float q1q2 = q1 * q2;
+ float q1q3 = q1 * q3;
+ float q1q4 = q1 * q4;
+ float q2q2 = q2 * q2;
+ float q2q3 = q2 * q3;
+ float q2q4 = q2 * q4;
+ float q3q3 = q3 * q3;
+ float q3q4 = q3 * q4;
+ float q4q4 = q4 * q4;
+
+ // Normalise accelerometer measurement
+ norm = sqrt(ax * ax + ay * ay + az * az);
+ if (norm == 0.0f) return; // handle NaN
+ norm = 1.0f / norm; // use reciprocal for division
+ ax *= norm;
+ ay *= norm;
+ az *= norm;
+
+ // Normalise magnetometer measurement
+ norm = sqrt(mx * mx + my * my + mz * mz);
+ if (norm == 0.0f) return; // handle NaN
+ norm = 1.0f / norm; // use reciprocal for division
+ mx *= norm;
+ my *= norm;
+ mz *= norm;
+
+ // Reference direction of Earth's magnetic field
+ hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
+ hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
+ bx = sqrt((hx * hx) + (hy * hy));
+ bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
+
+ // Estimated direction of gravity and magnetic field
+ vx = 2.0f * (q2q4 - q1q3);
+ vy = 2.0f * (q1q2 + q3q4);
+ vz = q1q1 - q2q2 - q3q3 + q4q4;
+ wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
+ wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
+ wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
+
+ // Error is cross product between estimated direction and measured direction of gravity
+ ex = (ay * vz - az * vy) + (my * wz - mz * wy);
+ ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
+ ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
+ if (Ki > 0.0f)
+ {
+ eInt[0] += ex; // accumulate integral error
+ eInt[1] += ey;
+ eInt[2] += ez;
+ }
+ else
+ {
+ eInt[0] = 0.0f; // prevent integral wind up
+ eInt[1] = 0.0f;
+ eInt[2] = 0.0f;
+ }
+
+ // Apply feedback terms
+ gx = gx + Kp * ex + Ki * eInt[0];
+ gy = gy + Kp * ey + Ki * eInt[1];
+ gz = gz + Kp * ez + Ki * eInt[2];
+
+ // Integrate rate of change of quaternion
+ pa = q2;
+ pb = q3;
+ pc = q4;
+ q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
+ q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
+ q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
+ q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
+
+ // Normalise quaternion
+ norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
+ norm = 1.0f / norm;
+ q[0] = q1 * norm;
+ q[1] = q2 * norm;
+ q[2] = q3 * norm;
+ q[3] = q4 * norm;
+
+ }
+ };
+#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Rawserial.bld Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed/builds/fd96258d940d \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/SDFileSystem.lib Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/teams/1519026547/code/SDFileSystem3/#85fbe134acff
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/config/SkipperSv2.h Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,22 @@ +#ifndef SKIPPERSV2_H_ +#define SKIPPERSV2_H_ + +/*フライトモードの変数================ + ModeBreak モードブレイク 状態変更時に1回だけ呼び出して、現在実行中のRTOSタスクを全部無効にする + StartUP 初期化モード まず最初に呼び出して、各種設定を有効にし、機体のチェック等を行う + ManualMode 手動飛行モード 通常のラジコンと同じ状態 + AutoLoop 自動操縦 水平旋回モード + AutoMobius 自動操縦 8の字飛行モード + AutoClimb 自動操縦 上昇旋回 + AutoGlide 自動操縦 自動滑空 + AutoLanding 自動操縦 自動着陸 +*/ + + #define MAGBIASX 0 //-63 + #define MAGBIASY 0 //580 + #define MAGBIASZ 0 //132 + +bool Flag_ChangeMode=true; //モードを切り替えた瞬間を検出してtrueを返す モード変更が直ちに行われ、falseになる。 +//=========== end ============= + +#endif /* SKIPPERSV2_H_ */ \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/config/falfalla.h Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,84 @@
+#ifndef FALFALLA_H
+#define FALFALLA_H
+
+#define SWITCH_CHECK 1400
+#define NUMBER_FALFALLA 2 //何号機かを入れるとそれに応じて#if以下が変わって設定が変わる
+
+static float g_kpELE=2.0;
+static float g_kiELE=0.0;
+static float g_kdELE=0.0;
+static float g_kpRUD=3.0;
+static float g_kiRUD=0.0;
+static float g_kdRUD=0.0;
+static float g_kpAIL=3.0;
+static float g_kiAIL=0.0;
+static float g_kdAIL=0.0;
+
+static float g_rightloopROLL=-17.0;
+static float g_rightloopROLL_approach=-17.0;
+static float g_rightloopPITCH=-6.3;
+static float g_rightloopPITCH_approach = -15.0;
+static float g_leftloopROLL=-16.0;
+static float g_leftloopROLL_approach=16.0;
+static float g_leftloopPITCH=-6.0;
+static float g_leftloopPITCH_approach=-13.0;
+static float g_gostraightROLL=0.0;
+static float g_gostraightPITCH=-3.0;
+static float g_takeoffTHR=1.0;
+static float g_loopTHR=0.58;
+static float g_ascendingPITCH=-40.0; //上昇旋回
+static int g_take_off_THROTTLE=2500;
+static float g_take_off_PITCH = -10;
+static float g_rightloop_THR_rate = 0.75;
+static float g_leftloop_THR_rate = 0.75;
+static float g_ascending_THR_rate = 0.8;
+static float g_ascending_ROLL = 0;
+static int g_ascending_RUD = 1500;
+
+static float g_rightloopROLLshort=-20.0;
+static float g_rightloopPITCHshort=-7.0;
+static float g_leftloopROLLshort=22.0;
+static float g_leftloopPITCHshort=-6.0;
+
+static float g_glideloopROLL = -5.0; //rewrite
+static float g_glideloopPITCH = 0.0;
+static float g_autoonPITCH = -20.0;
+
+static int g_rightloopRUD = 1500;
+static int g_rightloopRUD_approach=1500;
+static int g_rightloopshortRUD = 1500;
+static int g_leftloopRUD = 1000;
+static int g_leftloopRUD_approach = 1710;
+static int g_leftloopshortRUD = 1500;
+static int g_glideloopRUD = 1500;
+
+static int g_AIL_L_correctionrightloop = 0;
+static int g_AIL_L_correctionrightloopshort = 0;
+static int g_AIL_L_correctionleftloop = 0;
+static int g_AIL_L_correctionleftloopshort = 0;
+
+static int g_trim1 = 1428;
+static int g_trim2 = 1645;
+static int g_trim3 = 1150;
+static int g_trim4 = 1490;
+static int g_trim5 = 1344;
+static int g_trim6 = 1478;
+static bool g_trim_check = 0;
+
+
+#if NUMBER_FALFALLA == 1 //1号機
+const int8_t Reverce_falfalla[4] = {1,-1,1,1}; //Nutral:1 , Reverce:-1
+
+#elif NUMBER_FALFALLA == 2 //2号機
+const int16_t Reverce_falfalla[4] = {1,-1,1,-1}; //Nutral:1 , Reverce:-1
+
+#endif
+
+
+#endif /* ESTRELA_H_ */
+
+/*
+x軸回り ロール
+y軸回り ピッチ
+z軸回り ヨー
+*/
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,2502 @@
+//mbed
+#include "mbed.h"
+#include "FATFileSystem.h"
+#include "SDFileSystem.h"
+//C
+#include "math.h"
+//sensor
+#include "MPU6050_DMP6.h"
+//#include "MPU9250.h"
+#include "MPU9250_BMP.h"
+#include "BMP280.h"
+#include "hcsr04.h"
+//device
+#include "sbus.h"
+//config
+#include "SkipperSv2.h"
+#include "falfalla.h"
+//other
+#include "pid.h"
+
+#define DEBUG_SEMIAUTO 0
+#define DEBUG_PRINT_INLOOP 1
+
+#define KP_ELE 16.5//15.0 //2.0
+#define KI_ELE 0.0
+#define KD_ELE 0.1 //0/0
+#define KP_RUD 3.0
+#define KI_RUD 0.0
+#define KD_RUD 0.0
+#define KP_AIL 0.11//0.1
+#define KI_AIL 0.2
+#define KD_AIL 0.2
+
+//#define g_AIL_L_Ratio_rightloop 0.5
+
+#define GAIN_CONTROLVALUE_TO_PWM 3.0
+
+#define RIGHT_ROLL 5.0//10
+#define RIGHT_PITCH 45//-20.0//-22//-24.0 //5.0
+#define LEFT_ROLL 15//-38.0//30
+
+#define LEFT_PITCH 10//-15.0
+#define STRAIGHT_ROLL 0.0//12.0//8.0
+#define STRAIGHT_PITCH 3.0
+#define TAKEOFF_THR 0.8
+#define LOOP_THR 0.6
+
+//#define g_rightloopRUD 1500
+
+#define RIGHT_ROLL_SHORT 10.0
+#define RIGHT_PITCH_SHORT -25.0
+#define LEFT_ROLL_SHORT -30.0
+#define LEFT_PITCH_SHORT -20.0
+#define RIGHTLOOPROLL_APPROACH 10.0
+#define LEFTLOOPROLL_APPROACH -30.0
+#define RIGHTLOOPPITCH_APPROACH -25.0
+#define LEFTLOOPPITCH_APPROACH -30.0
+
+#define ASCENDING_PITCH -35.0
+#define TAKE_OFF_THROTTLE 1650
+#define TAKE_OFF_PITCH 50//-40.0
+
+#define rightloopROLL2 -10.0
+
+/*#define rightloopRUD 1300 //1250
+#define rightloopshortRUD 1250
+#define leftloopRUD 1500
+#define leftloopshortRUD 1500
+#define glideloopRUD 1300
+*/
+#define AIL_R_correctionrightloop 0
+#define AIL_L_correctionrightloop 0
+#define AIL_L_correctionrightloopshort 0
+#define AIL_L_correctionleftloop -0
+#define AIL_L_correctionleftloopshort 0
+
+
+#define RIGHTLOOP_RUD 1190//1150 //1200
+#define RIGHTLOOPSHORT_RUD 1250
+#define LEFTLOOP_RUD 1560 //1680//1750//1700
+#define LEFTLOOPSHORT_RUD 1500
+#define GLIDELOOP_RUD 1300
+#define RIGHTLOOPRUD_APPROACH 1500
+#define LEFTLOOPRUD_APPROACH 1500
+#define RIGHTLOOP_THR_RATE 0.64//0.66
+#define LEFTLOOP_THR_RATE 0.49//0.62//0.66
+#define ASCENDING_THR_RATE 0.75
+#define ASCENDING_ROLL 16.0
+#define ASCENDING_RUD 1200
+
+
+#define AIL_L_CORRECTION_RIGHTLOOP 0
+#define AIL_L_CORRECTION_RIGHTLOOPSHORT 0
+#define AIL_L_CORRECTION_LEFTLOOP 0
+#define AIL_L_CORRECTION_LEFTLOOPSHORT 0
+
+
+
+#define TRIM1 1480
+#define TRIM2 1500
+#define TRIM3 1150
+#define TRIM4 1500
+#define TRIM5 1300
+#define TRIM6 1500
+#define TRIM_CHECK 0
+
+#define GLIDE_ROLL -12.0
+#define GLIDE_PITCH -3.0
+
+
+#define AIL_L_RatioRising 0.5
+#define AIL_L_RatioDescent 2
+
+//コンパスキャリブレーション
+//SkipperS2基板
+/*
+#define MAGBIAS_X -35.0
+#define MAGBIAS_Y 535.0
+#define MAGBIAS_Z -50.0
+*/
+//S2v2 1番基板
+#define MAGBIAS_X 395.0
+#define MAGBIAS_Y 505.0
+#define MAGBIAS_Z -725.0
+//S2v2 2番基板
+/*
+#define MAGBIAS_X 185.0
+#define MAGBIAS_Y 220.0
+#define MAGBIAS_Z -350.0
+*/
+
+#define ELEMENT 1
+#define LIMIT_STRAIGHT_YAW 5.0
+#define THRESHOLD_TURNINGRADIUS_YAW 60.0
+#define ALLOWHEIGHT 15
+
+//気圧用
+#define SBUS_SIGNAL_OK 0x00
+#define SBUS_SIGNAL_LOST 0x01
+#define SBUS_SIGNAL_FAILSAFE 0x03
+MPU9250 mpu9250;
+float g_sum = 0; //グローバルなので要注意!!
+uint32_t g_sumCount = 0;
+float g_grav = 9.80665;
+float g_st_press = 1018.5;
+float g_press, g_BMPheight;
+int g_BMPheight_int = 0;
+float g_InitPress[101];
+float g_InitPressAve = 0;
+float g_InitBMPHeight[101];
+float g_InitBMPHeightAve = 0;
+int g_temporary;
+float g_dt = 0.0;
+float g_v_prev = 0.0;
+float g_z_prev;
+float g_z_PressHeight, g_z_AccelHeight;
+float g_z_comp;
+float g_tempaz[2];
+
+BMP280 bmp(PC_9, PA_8);
+Timer tBMP;
+
+
+#ifndef PI
+#define PI 3.14159265358979
+#endif
+
+const int16_t lengthdivpwm = 320;
+const int16_t changeModeCount = 6;
+
+
+SBUS sbus(PA_9, PA_10); //SBUS
+
+PwmOut servo1(PC_6); // TIM3_CH1 //old echo
+PwmOut servo2(PC_7); // TIM3_CH2 //PC_7
+PwmOut servo3(PB_0); // TIM3_CH3
+PwmOut servo4(PB_1); // TIM3_CH4
+PwmOut servo5(PB_6); // TIM4_CH1
+PwmOut servo6(PB_7); // TIM4_CH2 //old trigger
+//PwmOut servo7(PB_8); // TIM4_CH3 //PB_8 new echo
+//PwmOut servo8(PB_9); // TIM4_CH4 //new trigger
+
+RawSerial pc(PA_2,PA_3, 115200); //tx,rx.baudrate pin;PA_2=UART2_TX, PA_3=UART2_RX
+//RawSerial pc2(PB_6,PB_7, 115200); //sbus確認用
+SDFileSystem sd(PB_15, PB_14, PB_13, PB_12, "sd");
+
+DigitalOut led1(PA_0); //黄色のコネクタ
+DigitalOut led2(PA_1);
+DigitalOut led3(PB_5);
+DigitalOut led4(PB_4);
+
+//InterruptIn switch2(PC_14);
+MPU6050DMP6 mpu6050(PC_0,&pc); //割り込みピン,シリアルポインタ i2cのピン指定は MPU6050>>I2Cdev.h 内のdefine
+HCSR04 usensor(PB_9,PB_8); //trig,echo 9,8
+
+PID pid_AIL(g_kpAIL,g_kiAIL,g_kdAIL);
+PID pid_ELE(g_kpELE,g_kiELE,g_kdELE);
+PID pid_RUD(g_kpRUD,g_kiRUD,g_kdRUD);
+
+enum Channel {AIL_R, ELE, THR, RUD, DROP, AIL_L, Ch7, Ch8};
+enum Angle {ROLL, PITCH, YAW}; //yaw:北を0とした絶対角度
+enum OperationMode {StartUp, SemiAuto, RightLoop, LeftLoop, GoStraight, BombwithPC, ZERO, Moebius, Glide};
+enum BombingMode {Takeoff, Chicken, Transition, Approach};
+enum OutputStatus {Manual, Auto};
+
+static OutputStatus output_status = Manual;
+OperationMode operation_mode = StartUp;
+BombingMode bombing_mode = Takeoff;
+
+static int16_t autopwm[8] = {1514,1435,1180,1512,1176,1800};//6:1848
+
+//1号機14SG
+
+static int16_t trimpwm[6] = {1428,1646,1176,1476,1344,1478};//1500
+int16_t maxpwm[6] = {1786,1848,1848,1889,1520,1848};
+int16_t minpwm[6] = {1114,1384,500,1293,1280,1176};///3-1376
+const int16_t reverce[4] = {Reverce_falfalla[0],Reverce_falfalla[1],Reverce_falfalla[2],Reverce_falfalla[3]};
+
+
+//2号機
+/*
+static int16_t trimpwm[6] = {1508,1559,1184,1664,1072,1952};
+int16_t maxpwm[6] = {1840,1884,1840,1992,1728,1952};
+int16_t minpwm[6] = {1183,1228,1176,1420,1420,1072};
+const int16_t reverce[4] = {Reverce_falfalla[0],Reverce_falfalla[1],Reverce_falfalla[2],Reverce_falfalla[3]};
+*/
+
+int16_t oldTHR = 1000;
+
+int16_t g_AIL_L_Ratio_rightloop = 0.5;
+
+
+static float nowAngle[3] = {0,0,0};
+const float trimAngle[3] = {0.0, 0.0, 0.0};
+const float maxAngle[2] = {90, 90};
+const float minAngle[2] = {-90, -90};
+
+float FirstROLL = 0.0, FirstPITCH = 0.0,FirstYAW = 0.0;
+
+unsigned int g_distance;
+Ticker USsensor;
+static char g_buf[16];
+char g_landingcommand='T';
+float g_SerialTargetYAW;
+
+
+Timer t;
+Timer t2;
+Timeout RerurnChickenServo1;
+Timeout RerurnChickenServo2;
+
+/*-----関数のプロトタイプ宣言-----*/
+void setup();
+void loop();
+
+void Init_PWM();
+void Init_servo(); //サーボ初期化
+void Init_sbus(); //SBUS初期化
+void Init_sensors();
+void DisplayClock(); //クロック状態確認
+void SetupBMP280();
+void Set_trim();
+
+//センサの値取得
+void SensingMPU();
+void UpdateDist();
+void sensing();
+void getBMP280();
+
+//void offsetRollPitch(float FirstROLL, float FirstPITCH);
+//void TransYaw(float FirstYAW);
+float TranslateNewYaw(float beforeYaw, float newzeroYaw);
+void UpdateTargetAngle(float targetAngle[3]);
+void CalculateControlValue(float targetAngle[3], float controlValue[3]);
+void UpdateAutoPWM(float controlValue[3]);
+void ConvertPWMintoRAD(float targetAngle[3]);
+inline float CalcRatio(float value, float trim, float limit);
+bool CheckSW_Up(Channel ch);
+int16_t ThresholdMaxMin(int16_t value, int16_t max, int16_t min);
+inline int16_t SetTHRinRatio(float ratio);
+void Ascending(float targetAngle[3]);
+
+//sbus割り込み
+void Update_PWM(); //マニュアル・自動モードのpwmデータを整形しpwm変数に入力
+void Output_PWM(int16_t pwm[6]); //pwmをサーボへ出力
+
+//シリアル割り込み
+void getSF_Serial();
+float ConvertByteintoFloat(char high, char low);
+
+bool g_Finflag = false;
+
+
+//SD設定
+int GetParameter(FILE *fp, const char *paramName,char parameter[]);
+int SetOptions(float *g_kpELE, float *g_kiELE, float *g_kdELE,
+ float *g_kpRUD, float *g_kiRUD, float *g_kdRUD,
+ float *g_rightloopROLL, float *g_rightloopPITCH,
+ float *g_leftloopROLL, float *g_leftloopPITCH,
+ float *g_gostraightROLL, float *g_gostraightPITCH,
+ float *g_takeoffTHR, float *g_loopTHR,
+ float *g_rightloopROLLshort, float *g_rightloopPITCHshort,
+ float *g_leftloopROLLshort, float *g_leftloopPITCHshort,
+ float *g_glideloopROLL, float *g_glideloopPITCH,
+ float *g_kpAIL, float *g_kiAIL, float *g_kdAIL,
+ int *g_rightloopRUD, int *g_rightloopshortRUD,
+ int *g_leftloopRUD, int *g_leftloopshortRUD,
+ int *g_glideRUD,
+ float *g_rightloopROLL_approach, float *g_leftloopROLL_approach,
+ int *g_rightloopRUD_approach, int *g_leftloopRUD_approach,
+ float *g_rightloopPITCH_approach, float *g_leftloopPITCH_approach,
+ float *g_ascendingPITCH,
+ int *g_take_off_THROTTLE, float *g_take_off_PITCH,
+ float *g_rightloop_THR_rate, float *g_leftloop_THR_rate,
+ float *g_ascendding_thr_rate,
+ float *g_ascending_ROLL, int *g_ascending_RUD,
+ int *g_trim1, int *g_trim2, int *g_trim3,
+ int *g_trim4, int *g_trim5, int *g_trim6,
+ bool *g_trim_check
+ );
+//switch2割り込み
+void ResetTrim();
+
+//自動操縦
+void UpdateTargetAngle_GoStraight(float targetAngle[3]);
+void UpdateTargetAngle_GoStraight_zero(float targetAngle[3]); //着陸時にスロットルが0の時の直進
+void UpdateTargetAngle_Rightloop(float targetAngle[3]);
+void UpdateTargetAngle_Rightloop_short(float targetAngle[3]);
+void UpdateTargetAngle_Rightloop_zero(float targetAngle[3]); //着陸時にスロットルが0の時の右旋回
+void UpdateTargetAngle_Rightloop_UP(float targetAngle[3]);
+void UpdateTargetAngle_Leftloop(float targetAngle[3]);
+void UpdateTargetAngle_Leftloop_short(float targetAngle[3]);
+void UpdateTargetAngle_Leftloop_zero(float targetAngle[3]); //着陸時にスロットルが0の時の左旋回
+void UpdateTargetAngle_Moebius(float targetAngle[3]);
+void UpdateTargetAngle_Takeoff(float targetAngle[3]);
+void UpdateTargetAngle_Approach(float targetAngle[3]);
+void Take_off_and_landing(float targetAngle[3]);
+
+
+
+int Rotate(float targetAngle[3], float TargetYAW);
+int Rotate_zero(float targetAngle[3], float TargetYAW);
+
+//投下
+void Chicken_Drop();
+void ReturnChickenServo1();
+void ReturnChickenServo2();
+
+//超音波による高度補正
+void checkHeight(float targetAngle[3]);
+void UpdateTargetAngle_NoseUP(float targetAngle[3]);
+void UpdateTargetAngle_NoseDOWN(float targetAngle[3]);
+
+//デバッグ用
+void Sbusprintf();
+void DebugPrint();
+
+/*---関数のプロトタイプ宣言終わり---*/
+
+int main()
+{
+ setup();
+
+
+ while(1) {
+
+ loop();
+
+
+ NVIC_DisableIRQ(USART1_IRQn);
+ if(!CheckSW_Up(Ch7)) {
+ led3=0;
+
+ } else {
+ led3=1;
+ }
+ NVIC_EnableIRQ(USART1_IRQn);
+ }
+
+}
+
+void setup()
+{
+ //buzzer = 0;
+ led1 = 1;
+ led2 = 1;
+ led3 = 1;
+ led4 = 1;
+
+ SetOptions(&g_kpELE, &g_kiELE, &g_kdELE,
+ &g_kpRUD, &g_kiRUD, &g_kdRUD,
+ &g_rightloopROLL, &g_rightloopPITCH,
+ &g_leftloopROLL, &g_leftloopPITCH,
+ &g_gostraightROLL, &g_gostraightPITCH,
+ &g_takeoffTHR, &g_loopTHR,
+ &g_rightloopROLLshort, &g_rightloopPITCHshort,
+ &g_leftloopROLLshort, &g_leftloopPITCHshort,
+ &g_glideloopROLL, &g_glideloopPITCH,
+ &g_kpAIL, &g_kiAIL,&g_kdAIL,
+ &g_rightloopRUD, &g_rightloopshortRUD,
+ &g_leftloopRUD, &g_leftloopshortRUD,
+ &g_glideloopRUD,
+ &g_rightloopROLL_approach,&g_leftloopROLL_approach,
+ &g_rightloopRUD_approach,&g_leftloopRUD_approach,
+ &g_rightloopPITCH_approach,&g_leftloopPITCH_approach,
+ &g_ascendingPITCH,
+ &g_take_off_THROTTLE, &g_take_off_PITCH,
+ &g_rightloop_THR_rate, &g_leftloop_THR_rate,
+ &g_ascending_THR_rate,
+ &g_ascending_ROLL, &g_ascending_RUD,
+ &g_trim1, &g_trim2, &g_trim3,
+ &g_trim4, &g_trim5, &g_trim6,
+ &g_trim_check
+ );
+
+ Set_trim();
+
+
+
+ Init_PWM();
+ Init_servo();
+ Init_sbus();
+ Init_sensors();
+ //switch2.rise(ResetTrim);
+
+ USsensor.attach(&UpdateDist, 0.05);
+
+ NVIC_SetPriority(USART1_IRQn,0);//プロポ
+ NVIC_SetPriority(EXTI0_IRQn,1);//MPU割り込み禁止
+ NVIC_SetPriority(TIM5_IRQn,2);
+ NVIC_SetPriority(EXTI9_5_IRQn,3);
+ NVIC_SetPriority(EXTI4_IRQn,5);
+ DisplayClock();
+ t.start();
+ t.start();
+
+
+ pc.printf("MPU calibration start\r\n");
+
+ float offsetstart = t.read();
+ while(t.read() - offsetstart < 26) {
+ SensingMPU();
+ for(uint8_t i=0; i<3; i++) pc.printf("%3.2f\t",nowAngle[i]);
+ pc.printf("\r\n");
+ led1 = !led1;
+ led2 = !led2;
+ led3 = !led3;
+ led4 = !led4;
+ }
+ //pc.attach(getSF_Serial, Serial::RxIrq);
+ NVIC_SetPriority(USART2_IRQn,4);//シリアル
+
+ FirstROLL = nowAngle[ROLL];
+ FirstPITCH = nowAngle[PITCH];
+ nowAngle[ROLL] -=FirstROLL;
+ nowAngle[PITCH] -=FirstPITCH;
+
+ SetupBMP280();
+
+// NVIC_EnableIRQ(USART2_IRQn);
+//
+// if(pc.readable()) { // 受信確認
+//
+// static char SFbuf[16]= {'Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q'};
+// SFbuf[0] = pc.getc(); // 1文字取り出し
+// if(SFbuf[0]=='S') {
+// for(int i=0;i<3;i++){
+// led1 = 1;
+// led2 = 1;
+// led3 = 1;
+// led4 = 1;
+// wait(0.2);
+// }
+// }
+// }
+// NVIC_DisableIRQ(USART2_IRQn);
+
+
+ led1 = 0;
+ led2 = 0;
+ led3 = 0;
+ led4 = 0;
+ wait(0.2);
+
+
+ pc.printf("All initialized\r\n");
+}
+
+void Set_trim(){
+ trimpwm[0] = g_trim1;
+ trimpwm[1] = g_trim2;
+ trimpwm[2] = g_trim3;
+ trimpwm[3] = g_trim4;
+ trimpwm[4] = g_trim5;
+ trimpwm[5] = g_trim6;
+
+ maxpwm[0] = 1768;//trimpwm[0] + 330;
+ maxpwm[1] = 1964;//trimpwm[1] + 330;
+ maxpwm[2] = 1848;//trimpwm[2] + 660;
+ maxpwm[3] = 1825;//trimpwm[3] + 330;
+ maxpwm[4] = 1914;//trimpwm[4] + 660;
+ maxpwm[5] = 1816;//trimpwm[5] + 330;
+
+ minpwm[0]= 1186;//trimpwm[0] - 330;
+ minpwm[1]= 1314;//trimpwm[1] - 330;
+ minpwm[2]= trimpwm[2] - 0;
+ minpwm[3]= 1154;//trimpwm[3] - 330;
+ minpwm[4]= 1344;//trimpwm[4] - 0;
+ minpwm[5]= 1144;//trimpwm[5] - 330;
+}
+
+void loop()
+{
+ static float targetAngle[3] = {0.0, 0.0, 0.0}, controlValue[2] = {0.0, 0.0};
+ SensingMPU();
+ UpdateTargetAngle(targetAngle);
+ CalculateControlValue(targetAngle, controlValue);
+ UpdateAutoPWM(controlValue);
+
+
+ //NVIC_SetPriority(TIM5_IRQn,4);
+ //NVIC_SetPriority(USART2_IRQn,2);
+
+ //wait_ms(23);
+ wait_ms(30);
+
+ //NVIC_SetPriority(TIM5_IRQn,2);
+ //NVIC_SetPriority(USART2_IRQn,4);
+
+
+ // pc.printf("6\r\n");
+ //NVIC_DisableIRQ(USART2_IRQn);
+ //pc.printf("%c",g_landingcommand);
+ //NVIC_EnableIRQ(USART2_IRQn);
+#if DEBUG_PRINT_INLOOP
+ //Sbusprintf();
+ DebugPrint();
+#endif
+}
+
+//サーボ初期化関数
+void Init_servo()
+{
+ servo1.period_ms(16);
+ servo1.pulsewidth_us(trimpwm[AIL_R]);
+
+ servo2.period_ms(16);
+ servo2.pulsewidth_us(trimpwm[ELE]);
+
+ servo3.period_ms(16);
+ servo3.pulsewidth_us(trimpwm[THR]);
+
+ servo4.period_ms(16);
+ servo4.pulsewidth_us(trimpwm[RUD]);
+
+ servo5.period_ms(16);
+ servo5.pulsewidth_us(trimpwm[DROP]);
+
+ servo6.period_ms(16);
+ servo6.pulsewidth_us(trimpwm[AIL_L]);
+
+ int i = 0;
+
+ for(i = 0;i<6;i++ ){
+ autopwm[i]=trimpwm[i];
+ }
+
+ pc.printf("servo initialized\r\n");
+}
+
+//Sbus初期化
+void Init_sbus()
+{
+ sbus.initialize();
+ sbus.setLastfuncPoint(Update_PWM);
+ sbus.startInterrupt();
+}
+
+void Init_sensors()
+{
+ if(mpu6050.setup() == -1) {
+ pc.printf("failed initialize\r\n");
+ while(1) {
+ led1 = 1;
+ led2 = 0;
+ led3 = 1;
+ led4 = 0;
+ wait(1);
+ led1 = 0;
+ led2 = 1;
+ led3 = 0;
+ led4 = 1;
+ wait(1);
+ }
+ }
+}
+
+void Init_PWM()
+{
+ pc.printf("PWM initialized\r\n");
+}
+
+void DisplayClock()
+{
+ pc.printf("System Clock = %d[MHz]\r\n", HAL_RCC_GetSysClockFreq()/1000000);
+ pc.printf("HCLK Clock = %d[MHz]\r\n", HAL_RCC_GetHCLKFreq()/1000000);
+ pc.printf("PCLK1 Clock = %d[MHz]\r\n", HAL_RCC_GetPCLK1Freq()/1000000);
+ pc.printf("PCLK2 Clock = %d[MHz]\r\n", HAL_RCC_GetPCLK2Freq()/1000000);
+ pc.printf("\r\n");
+}
+
+void UpdateTargetAngle(float targetAngle[3])
+{
+
+
+ static int16_t count_op = 0;
+#if DEBUG_SEMIAUTO
+ switch(operation_mode) {
+ case StartUp:
+ if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)) {
+ count_op++;B
+ if(count_op > changeModeCount) {
+ operation_mode = SemiAuto;
+ pc.printf("Goto SemiAuto mode\r\n");
+ count_op = 0;
+ }
+ } else count_op = 0;
+ break;
+
+ case SemiAuto:
+ /* 大会用では以下のif文を入れてoperation_modeを変える
+ if(CheckSW_Up(Ch6)){
+ count_op++;
+ if(count_op>changeModeCount){
+ output_status = XXX;
+ led2 = 0;
+ pc.printf("Goto XXX mode\r\n");
+ count_op = 0;
+ }else count_op = 0;
+ ConvertPWMintoRAD(targetAngle);
+ }
+ */
+ ConvertPWMintoRAD(targetAngle);
+ break;
+
+ default:
+ operation_mode = SemiAuto;
+ break;
+ }
+
+#else
+
+ switch(operation_mode) {
+ case StartUp:
+ if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)) { //ch7;自動・手動切り替え ch8;自動操縦モード切替
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = LeftLoop;
+ pc.printf("Goto LeftLoop mode\r\n");
+ count_op = 0;
+ }
+ } else count_op = 0;
+ break;
+
+ case LeftLoop:
+ if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)) {
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = GoStraight;
+ pc.printf("Goto GoStraight mode\r\n");
+ count_op = 0;
+ }
+ } else count_op = 0;
+ UpdateTargetAngle_Leftloop(targetAngle);
+ //UpdateTargetAngle_GoStraight_zero(targetAngle);
+ break;
+
+ case GoStraight:
+ if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)) {
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = Moebius;
+ pc.printf("Goto Moebius mode\r\n");
+ count_op = 0;
+ }
+ } else count_op = 0;
+ //UpdateTargetAngle_GoStraight(targetAngle);
+ UpdateTargetAngle_GoStraight_zero(targetAngle);
+ //UpdateTargetAngle_Leftloop_short(targetAngle);
+ //UpdateTargetAngle_Leftloop_zero(targetAngle);
+
+
+ break;
+
+ case Moebius:
+ if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)) {
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = Glide;
+ pc.printf("Goto Glide mode\r\n");
+ count_op = 0;
+ }
+ } else count_op = 0;
+ UpdateTargetAngle_Moebius(targetAngle);
+ break;
+
+ case Glide:
+ if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)) {
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = RightLoop;
+ pc.printf("Goto RightLoop mode\r\n");
+ count_op = 0;
+ }
+ } else count_op = 0;
+ //UpdateTargetAngle_Rightloop_short(targetAngle);
+ //UpdateTargetAngle_Rightloop_zero(targetAngle);
+ UpdateTargetAngle_GoStraight_zero(targetAngle);
+
+ break;
+
+ case RightLoop:
+ if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)) {
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = BombwithPC;
+ pc.attach(getSF_Serial, Serial::RxIrq);
+ autopwm[DROP]=trimpwm[DROP];
+ pc.printf("Goto BombwithPC mode\r\n");
+ //g_AscendingFlag = false;
+ count_op = 0;
+ }
+ } else count_op = 0;
+ Ascending(targetAngle);
+ break;
+
+ case BombwithPC:
+ if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)) {
+ count_op++;
+ if(count_op > changeModeCount) {
+ operation_mode = LeftLoop;
+ pc.printf("Goto Left mode\r\n");
+ pc.attach(NULL, Serial::RxIrq);
+ count_op = 0;
+ }
+ } else count_op = 0;
+ Take_off_and_landing(targetAngle);
+ break;
+
+ default:
+ operation_mode = StartUp;
+ break;
+ }
+#endif
+
+ if(CheckSW_Up(Ch7)) {
+ output_status = Auto;
+ led1 = 1;
+ } else {
+ output_status = Manual;
+ led1 = 0;
+ }
+
+
+}
+
+int GetParameter(FILE *fp, const char *paramName,char parameter[])
+{
+ int i=0, j=0;
+ int strmax = 200;
+ char str[strmax];
+
+ rewind(fp); //ファイル位置を先頭に
+ while(1) {
+ if (fgets(str, strmax, fp) == NULL) {
+ return 0;
+ }
+ if (!strncmp(str, paramName, strlen(paramName))) {
+ while (str[i++] != '=') {}
+ while (str[i] != '\n') {
+ parameter[j++] = str[i++];
+ }
+ parameter[j] = '\0';
+ return 1;
+ }
+ }
+}
+
+
+//sdによる設定
+int SetOptions(float *g_kpELE, float *g_kiELE, float *g_kdELE,
+ float *g_kpRUD, float *g_kiRUD, float *g_kdRUD,
+ float *g_rightloopROLL, float *g_rightloopPITCH,
+ float *g_leftloopROLL, float *g_leftloopPITCH,
+ float *g_gostraightROLL, float *g_gostraightPITCH,
+ float *g_takeoffTHR, float *g_loopTHR,
+ float *g_rightloopROLLshort, float *g_rightloopPITCHshort,
+ float *g_leftloopROLLshort, float *g_leftloopPITCHshort,
+ float *g_glideloopROLL, float *g_glideloopPITCH,
+ float *g_kpAIL, float *g_kiAIL, float *g_kdAIL,
+ int *g_rightloopRUD, int *g_rightloopshortRUD,
+ int *g_leftloopRUD, int *g_leftloopshortRUD,
+ int *g_glideloopRUD,
+ float *g_rightloopROLL_approach,float *g_leftloopROLL_approach,
+ int *g_rightloopRUD_approach,int *g_leftloopRUD_approach,
+ float *g_rightloopPITCH_approach,float *g_leftloopPITCH_approach,
+ float *g_ascendingPITCH,
+ int *g_take_off_THROTTLE, float *g_take_off_PITCH,
+ float *g_rightloop_THR_rate, float *g_leftloop_THR_rate,
+ float *g_ascending_THR_rate,
+ float *g_ascending_ROLL, int *g_ascending_RUD,
+ int *g_trim1, int *g_trim2, int *g_trim3,
+ int *g_trim4, int *g_trim5, int *g_trim6,
+ bool *g_trim_check
+ )
+{
+
+ pc.printf("SDsetup start.\r\n");
+
+ FILE *fp;
+ char parameter[50]; //文字列渡す用の配列
+ int SDerrorcount = 0; //取得できなかった数を返す
+ const char *paramNames[] = {
+ "KP_ELEVATOR",
+ "KI_ELEVATOR",
+ "KD_ELEVATOR",
+ "KP_RUDDER",
+ "KI_RUDDER",
+ "KD_RUDDER",
+ "RIGHTLOOP_ROLL",
+ "RIGHTLOOP_PITCH",
+ "LEFTLOOP_ROLL",
+ "LEFTLOOP_PITCH",
+ "GOSTRAIGHT_ROLL",
+ "GOSTRAIGHT_PITCH",
+ "TAKEOFF_THR_RATE",
+ "LOOP_THR_RATE",
+ "RIGHTLOOP_ROLL_SHORT",
+ "RIGHTLOOP_PITCH_SHORT",
+ "LEFTLOOP_ROLL_SHORT",
+ "LEFTLOOP_PITCH_SHORT",
+ "AUTOGLIDE_ROLL",
+ "AUTOGLIDE PITCH",
+ "KP_AILERON",
+ "KI_AILERON",
+ "KD_AILERON",
+ "RIGHTLOOP_RUDDER",
+ "RIGHTLOOPSHORT_RUDDER",
+ "LEFTLOOP_RUDDER",
+ "LEFTLOOPSHORT_RUDDER",
+ "GLIDELOOP_RUDDER",
+ "RIGHTLOOP_ROLL_APPROACH",
+ "LEFTLOOP_ROLL_APPROACH",
+ "RIGHTLOOP_RUDDER_APPROACH",
+ "LEFTLOOP_RUDDER_APPROACH",
+ "RIGHTLOOP_PITCH_APPROACH",
+ "LEFTLOOP_PITCH_APPROACH",
+ "ASCENDING_PITCH",
+ "TAKE_OFF_THROTTLE",
+ "TAKE_OFF_PITCH",
+ "RIGHTLOOP_THR_RATE",
+ "LEFTLOOP_THR_RATE",
+ "ASCENDING_THR_RATE",
+ "ASCENDING_ROLL",
+ "ASCENDING_RUD",
+ "TRIM1",
+ "TRIM2",
+ "TRIM3",
+ "TRIM4",
+ "TRIM5",
+ "TRIM6",
+ "TRIM_CHECK"
+ };
+
+ fp = fopen("/sd/option.txt","r");
+
+ if(fp != NULL) { //開けたら
+ pc.printf("File was openned.\r\n");
+ if(GetParameter(fp,paramNames[0],parameter)) *g_kpELE = atof(parameter);
+ else {
+ *g_kpELE = KP_ELE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[1],parameter)) *g_kiELE = atof(parameter);
+ else {
+ *g_kiELE = KI_ELE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[2],parameter)) *g_kdELE = atof(parameter);
+ else {
+ *g_kdELE = KD_ELE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[3],parameter)) *g_kpRUD = atof(parameter);
+ else {
+ *g_kpRUD = KP_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[4],parameter)) *g_kiRUD = atof(parameter);
+ else {
+ *g_kiRUD = KI_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[5],parameter)) *g_kdRUD = atof(parameter);
+ else {
+ *g_kdRUD = KD_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[6],parameter)) *g_rightloopROLL = atof(parameter);
+ else {
+ *g_rightloopROLL = RIGHT_ROLL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[7],parameter)) *g_rightloopPITCH = atof(parameter);
+ else {
+ *g_rightloopPITCH = RIGHT_PITCH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[8],parameter)) *g_leftloopROLL = atof(parameter);
+ else {
+ *g_leftloopROLL = LEFT_ROLL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[9],parameter)) *g_leftloopPITCH = atof(parameter);
+ else {
+ *g_leftloopPITCH = LEFT_PITCH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[10],parameter)) *g_gostraightROLL = atof(parameter);
+ else {
+ *g_gostraightROLL = STRAIGHT_ROLL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[11],parameter)) *g_gostraightPITCH = atof(parameter);
+ else {
+ *g_gostraightPITCH = STRAIGHT_PITCH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[12],parameter)) *g_takeoffTHR = atof(parameter);
+ else {
+ *g_takeoffTHR = TAKEOFF_THR;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[13],parameter)) *g_loopTHR = atof(parameter);
+ else {
+ *g_loopTHR = LOOP_THR;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[14],parameter)) *g_rightloopROLLshort = atof(parameter);
+ else {
+ *g_rightloopROLLshort = RIGHT_ROLL_SHORT;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[15],parameter)) *g_rightloopPITCHshort = atof(parameter);
+ else {
+ *g_rightloopPITCHshort = RIGHT_PITCH_SHORT;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[16],parameter)) *g_leftloopROLLshort = atof(parameter);
+ else {
+ *g_leftloopROLLshort = LEFT_ROLL_SHORT;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[17],parameter)) *g_leftloopPITCHshort = atof(parameter);
+ else {
+ *g_leftloopPITCHshort = LEFT_PITCH_SHORT;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[18],parameter)) *g_glideloopROLL = atof(parameter);
+ else {
+ *g_glideloopROLL = GLIDE_ROLL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[19],parameter)) *g_glideloopPITCH = atof(parameter);
+ else {
+ *g_glideloopPITCH = GLIDE_PITCH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[20],parameter)) *g_kpAIL = atof(parameter);
+ else {
+ *g_kpAIL = KP_AIL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[21],parameter)) *g_kiAIL = atof(parameter);
+ else {
+ *g_kiAIL = KI_AIL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[22],parameter)) *g_kdAIL = atof(parameter);
+ else {
+ *g_kdAIL = KP_AIL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[23],parameter)) *g_rightloopRUD = atof(parameter);
+ else {
+ *g_rightloopRUD = RIGHTLOOP_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[24],parameter)) *g_rightloopshortRUD = atof(parameter);
+ else {
+ *g_rightloopshortRUD = RIGHTLOOPSHORT_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[25],parameter)) *g_leftloopRUD = atof(parameter);
+ else {
+ *g_leftloopshortRUD = LEFTLOOP_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[26],parameter)) *g_leftloopshortRUD = atof(parameter);
+ else {
+ *g_leftloopshortRUD = LEFTLOOPSHORT_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[27],parameter)) *g_glideloopRUD = atof(parameter);
+ else {
+ *g_glideloopRUD = GLIDELOOP_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[28],parameter)) *g_rightloopROLL_approach = atof(parameter);
+ else {
+ *g_rightloopROLL_approach = RIGHTLOOPROLL_APPROACH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[29],parameter)) *g_leftloopROLL_approach= atof(parameter);
+ else {
+ *g_leftloopROLL_approach = LEFTLOOPROLL_APPROACH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[30],parameter)) *g_rightloopRUD_approach = atof(parameter);
+ else {
+ *g_rightloopRUD_approach = RIGHTLOOPRUD_APPROACH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[31],parameter)) *g_leftloopRUD_approach= atof(parameter);
+ else {
+ *g_leftloopRUD_approach= LEFTLOOPRUD_APPROACH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[32],parameter)) *g_rightloopPITCH_approach = atof(parameter);
+ else {
+ *g_rightloopPITCH_approach = RIGHTLOOPPITCH_APPROACH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[33],parameter)) *g_leftloopPITCH_approach = atof(parameter);
+ else {
+ *g_leftloopPITCH_approach = LEFTLOOPPITCH_APPROACH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[34],parameter)) *g_ascendingPITCH = atof(parameter);
+ else {
+ *g_ascendingPITCH = ASCENDING_PITCH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[35],parameter)) *g_take_off_THROTTLE = atof(parameter);
+ else {
+ *g_take_off_THROTTLE = TAKE_OFF_THROTTLE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[36],parameter)) *g_take_off_PITCH = atof(parameter);
+ else {
+ *g_take_off_PITCH = TAKE_OFF_PITCH;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[37],parameter)) *g_rightloop_THR_rate = atof(parameter);
+ else {
+ *g_rightloop_THR_rate = RIGHTLOOP_THR_RATE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[38],parameter)) *g_leftloop_THR_rate = atof(parameter);
+ else {
+ *g_leftloop_THR_rate = LEFTLOOP_THR_RATE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[39],parameter)) *g_ascending_THR_rate = atof(parameter);
+ else {
+ *g_ascending_THR_rate = ASCENDING_THR_RATE;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[40],parameter)) *g_ascending_ROLL = atof(parameter);
+ else {
+ *g_ascending_ROLL = ASCENDING_ROLL;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[41],parameter)) *g_ascending_RUD= atof(parameter);
+ else {
+ *g_ascending_RUD = ASCENDING_RUD;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[42],parameter)) *g_trim1 = atof(parameter);
+ else {
+ *g_trim1 = TRIM1;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[43],parameter)) *g_trim2 = atof(parameter);
+ else {
+ *g_trim2 = TRIM2;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[44],parameter)) *g_trim3 = atof(parameter);
+ else {
+ *g_trim3 = TRIM3;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[45],parameter)) *g_trim4 = atof(parameter);
+ else {
+ *g_trim4 = TRIM4;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[46],parameter)) *g_trim5 = atof(parameter);
+ else {
+ *g_trim5 = TRIM5;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[47],parameter)) *g_trim6 = atof(parameter);
+ else {
+ *g_trim6 = TRIM6;
+ SDerrorcount++;
+ }
+ if(GetParameter(fp,paramNames[48],parameter)) *g_trim_check = atof(parameter);
+ else {
+ *g_trim_check = TRIM_CHECK;
+ SDerrorcount++;
+ }
+
+
+ fclose(fp);
+
+ } else { //ファイルがなかったら
+ pc.printf("fp was null.\r\n");
+ *g_kpELE = KP_ELE;
+ *g_kiELE = KI_ELE;
+ *g_kdELE = KD_ELE;
+ *g_kpRUD = KP_RUD;
+ *g_kiRUD = KI_RUD;
+ *g_kdRUD = KD_RUD;
+ *g_rightloopROLL = RIGHT_ROLL;
+ *g_rightloopPITCH = RIGHT_PITCH;
+ *g_leftloopROLL = LEFT_ROLL;
+ *g_leftloopPITCH = LEFT_PITCH;
+ *g_gostraightROLL = STRAIGHT_ROLL;
+ *g_gostraightPITCH = STRAIGHT_PITCH;
+ *g_takeoffTHR = TAKEOFF_THR;
+ *g_loopTHR = LOOP_THR;
+ *g_kpAIL = KP_AIL; //パラメータ変えるのお忘れなく!!
+ *g_kiAIL = KI_AIL;
+ *g_kdAIL = KD_AIL;
+ *g_rightloopRUD = RIGHTLOOP_RUD;
+ *g_rightloopshortRUD = RIGHTLOOPSHORT_RUD;
+ *g_leftloopRUD = LEFTLOOP_RUD;
+ *g_leftloopshortRUD = LEFTLOOPSHORT_RUD;
+ *g_glideloopRUD = GLIDELOOP_RUD;
+ *g_rightloopROLL_approach = RIGHTLOOPROLL_APPROACH;
+ *g_leftloopROLL_approach = LEFTLOOPROLL_APPROACH;
+ *g_rightloopRUD_approach = RIGHTLOOPRUD_APPROACH;
+ *g_leftloopRUD_approach = LEFTLOOPRUD_APPROACH;
+ *g_rightloopPITCH_approach = RIGHTLOOPPITCH_APPROACH;
+ *g_leftloopPITCH_approach = LEFTLOOPPITCH_APPROACH;
+ *g_ascendingPITCH = ASCENDING_PITCH;
+ *g_take_off_THROTTLE = TAKE_OFF_THROTTLE;
+ *g_take_off_PITCH = TAKE_OFF_PITCH;
+ *g_rightloop_THR_rate = RIGHTLOOP_THR_RATE;
+ *g_leftloop_THR_rate = LEFTLOOP_THR_RATE;
+ *g_ascending_THR_rate = ASCENDING_THR_RATE;
+ *g_ascending_ROLL = ASCENDING_ROLL;
+ *g_ascending_RUD = ASCENDING_RUD;
+ *g_trim1 = TRIM1;
+ *g_trim2 = TRIM2;
+ *g_trim3 = TRIM3;
+ *g_trim4 = TRIM4;
+ *g_trim5 = TRIM5;
+ *g_trim6 = TRIM6;
+ *g_trim_check = TRIM_CHECK;
+
+ SDerrorcount = -1;
+ }
+ pc.printf("SDsetup finished.\r\n");
+ if(SDerrorcount == 0) pc.printf("setting option is success\r\n");
+ else if(SDerrorcount == -1) pc.printf("ERROR 1. cannot open option\r\n");
+ else if(SDerrorcount > 0) pc.printf("ERROR 2. reading parameter is failed[%d]\r\n",SDerrorcount);
+
+ pc.printf("kpELE = %f, kiELE = %f, kdELE = %f\r\n", *g_kpELE, *g_kiELE, *g_kdELE);
+ pc.printf("kpRUD = %f, kiRUD = %f, kdRUD = %f\r\n", *g_kpRUD, *g_kiRUD, *g_kdRUD);
+ pc.printf("rightloopROLL = %f, rightloopPITCH = %f\r\n", *g_rightloopROLL, *g_rightloopPITCH);
+ pc.printf("leftloopROLL = %f, g_leftloopPITCH = %f\r\n", *g_leftloopROLL, *g_leftloopPITCH);
+ pc.printf("gostraightROLL = %f, g_gostraightPITCH = %f\r\n", *g_gostraightROLL, *g_gostraightPITCH);
+ pc.printf("g_takeoffTHR = %f, g_loopTHR = %f\r\n", *g_takeoffTHR, *g_loopTHR);
+ pc.printf("rightloopROLLshort = %f, rightloopPITCHshort = %f\r\n", *g_rightloopROLLshort, *g_rightloopPITCHshort);
+ pc.printf("leftloopROLLshort = %f, g_leftloopPITCHshort = %f\r\n", *g_leftloopROLLshort, *g_leftloopPITCHshort);
+ pc.printf("glideROLL = %f, glidePITCH = %f\r\n", *g_glideloopROLL, *g_glideloopPITCH);
+ pc.printf("kpAIL = %f,kiAIL = %f,kdAIL = %f\r\n ",*g_kpAIL,*g_kiAIL,*g_kdAIL);
+ pc.printf("RIGHTLOOPRUD = %d,RIGHTLOOPSHORTRUD = %d\r\n",*g_rightloopRUD,*g_rightloopshortRUD);
+ pc.printf("LEFTTLOOPRUD = %d,LEFTLOOPSHORTRUD = %d\r\n",*g_leftloopRUD,*g_leftloopshortRUD);
+ pc.printf("GLIDELOOPRUD = %d\r\n",*g_glideloopRUD);
+ pc.printf("RIGHTLOOP_ROLL_APPROACH = %f, LEFTLOOP_ROLL_APPROACH= %f\r\n",*g_rightloopROLL_approach,*g_leftloopROLL_approach);
+ pc.printf("RIGHTLOOP_RUD_APPROACH = %d, LEFTLOOP_RUD_APPROACH = %d\r\n",*g_rightloopRUD_approach,*g_leftloopRUD_approach);
+ pc.printf("RIGHTLOOP_PITCH_APPROACH = %f, LEFTLOOP_PITCH_APPROACH = %f\r\n",*g_rightloopPITCH_approach,*g_leftloopPITCH_approach);
+ pc.printf("ASCENDING_PITCH = %f\r\n",*g_ascendingPITCH);
+ pc.printf("TAKE_OFF_THROTTLE = %d, TAKE_OFF_PITCH = %f\r\n",*g_take_off_THROTTLE,*g_take_off_PITCH);
+ pc.printf("RIGHTLOOP_THR_RATE = %f, LEFTLOOP_THR_RATE = %f, ASCENDING_THR_RATE = %f\r\n", *g_rightloop_THR_rate, *g_leftloop_THR_rate, *g_ascending_THR_rate);
+ pc.printf("ASCENDING_ROLL = %f,ASCENDING_RUD = %d\r\n",*g_ascending_ROLL,*g_ascending_RUD);
+ pc.printf("TRIM1 = %d, TRIM2 = %d, TRIM3 = %d\r\n",*g_trim1,*g_trim2,*g_trim3);
+ pc.printf("TRIM4 = %d, TRIM5 = %d, TRIM6 = %d\r\n",*g_trim4,*g_trim5,*g_trim6);
+ pc.printf("TRIM_CHECK = %d\r\n",*g_trim_check);
+
+ return SDerrorcount;
+}
+
+void CalculateControlValue(float targetAngle[3], float controlValue[3])
+{
+
+ static int t_last;
+ int t_now;
+ float dt;
+
+ t_now = t.read_us();
+ dt = (float)((t_now - t_last)/1000000.0f) ;
+ t_last = t_now;
+
+
+ //controlValue[ROLL] = pid_RUD.calcPID(nowAngle[ROLL], targetAngle[ROLL], dt);
+ controlValue[ROLL] = pid_AIL.calcPID(nowAngle[ROLL], targetAngle[ROLL], dt); //エルロンでロール制御
+ controlValue[PITCH] = pid_ELE.calcPID(nowAngle[PITCH], targetAngle[PITCH], dt);
+
+}
+
+void UpdateAutoPWM(float controlValue[3])
+{
+ NVIC_DisableIRQ(USART1_IRQn);
+ int16_t addpwm[2]; //-500~500
+ addpwm[PITCH] = (float)GAIN_CONTROLVALUE_TO_PWM * controlValue[PITCH]; //センサ:機首下げ正 レバー:機首上げ正
+ addpwm[ROLL] = (float)GAIN_CONTROLVALUE_TO_PWM * controlValue[ROLL]; //センサ:右回転正(8月13日時点;左回転が正!) レバー:右回転正
+
+ autopwm[ELE] = trimpwm[ELE] + reverce[ELE] * addpwm[PITCH]; //rewrite
+ autopwm[AIL_R] = trimpwm[AIL_R] - reverce[AIL_R] * addpwm[ROLL];
+ //autopwm[THR] = oldTHR;
+
+ autopwm[ELE] = ThresholdMaxMin(autopwm[ELE], maxpwm[ELE], minpwm[ELE]);
+ autopwm[AIL_R] = ThresholdMaxMin(autopwm[AIL_R], maxpwm[AIL_R], minpwm[AIL_R]);
+
+ NVIC_EnableIRQ(USART1_IRQn);
+}
+
+inline float CalcRatio(float value, float trim, float limit)
+{
+ return (value - trim) / (limit - trim);
+}
+
+bool CheckSW_Up(Channel ch)
+{
+
+ if(SWITCH_CHECK < sbus.manualpwm[ch]) {
+ return true;
+ } else {
+ return false;
+ }
+
+}
+
+int16_t ThresholdMaxMin(int16_t value, int16_t max, int16_t min)
+{
+ if(value > max) return max;
+ if(value < min) return min;
+ return value;
+}
+
+inline int16_t SetTHRinRatio(float ratio)
+{
+ return minpwm[THR] + (int16_t)(2 * lengthdivpwm * ratio);
+}
+
+
+
+/*---SBUS割り込み処理---*/
+
+//udate_Inputで抽出したpwmデータを整形して各変数に代入する。(マニュアルモード)
+//各stabiGylo関数で算出したpwmを各変数に代入する(自動モード)
+void Update_PWM()
+{
+ NVIC_DisableIRQ(USART1_IRQn);
+ static int16_t pwm[6];
+ static int16_t temppwm[6]= {trimpwm[0],trimpwm[1],trimpwm[2],trimpwm[3],trimpwm[4],trimpwm[5]};
+ static int16_t FailsafeCounter=0;
+ static int16_t ResetCounter=0;
+ static int16_t OKCounter=0;
+
+ if(sbus.flg_ch_update == true) {
+
+ switch(output_status) { //マニュアルモード,自動モード,自動着陸もモードを切替
+ case Manual:
+ if(OKCounter!=0) break;
+ for(uint8_t i=0; i<6; i++) {
+ pwm[i] = sbus.manualpwm[i];
+ }
+ oldTHR = sbus.manualpwm[THR];
+ //pc.printf("update_manual\r\n");
+ NVIC_EnableIRQ(USART1_IRQn);
+ break;
+
+ case Auto:
+ if(OKCounter!=0) break;
+ pwm[AIL_R] = autopwm[AIL_R]; //sbus.manualpwm[AIL];
+ pwm[ELE] = autopwm[ELE];
+ pwm[THR] = autopwm[THR];
+ pwm[RUD] = autopwm[RUD];
+ pwm[DROP] = autopwm[DROP];
+ pwm[AIL_L] = autopwm[AIL_L];
+
+ NVIC_EnableIRQ(USART1_IRQn);
+ break;
+
+ default:
+ if(OKCounter!=0) break;
+ for(uint8_t i=0; i<6; i++) {
+ pwm[i] = sbus.manualpwm[i];
+ } //pc.printf("update_manual\r\n");
+ NVIC_EnableIRQ(USART1_IRQn);
+ break;
+ }
+
+ for(uint8_t i=0; i<6; i++) {
+ if(pwm[i]<1000 || pwm[i]>2000) pwm[i]=temppwm[i];
+ temppwm[i]=pwm[i];
+ }
+
+ }
+ //else(sbus.flg_ch_update == false) pc.printf("0\r\n");
+ /* if(sbus.failsafe_status==SBUS_SIGNAL_OK){
+ pc.printf("OK\r\n");
+ }
+ */
+ //pc.printf("%d\r\n",sbus.failsafe_status);
+
+ if(sbus.failsafe_status==SBUS_SIGNAL_LOST||sbus.failsafe_status==SBUS_SIGNAL_FAILSAFE) FailsafeCounter++;
+ else ResetCounter++;
+
+ if(ResetCounter>7) {
+ ResetCounter=0;
+ FailsafeCounter=0;
+ }
+
+ if(FailsafeCounter>10) {
+ ResetCounter=0;
+ for(uint8_t i=0; i<6; i++) pwm[i] = trimpwm[i];
+
+ if(sbus.failsafe_status==SBUS_SIGNAL_OK&&sbus.flg_ch_update == true) OKCounter++;
+ else OKCounter=0;
+
+ if(OKCounter>10) {
+ OKCounter=0;
+ FailsafeCounter=0;
+ }
+ //pc.printf("OKCounter=%d, FailsafeCounter=%d, sbus.failsafe_status=%d\r\n",OKCounter,FailsafeCounter,sbus.failsafe_status);
+ }
+ //if(sbus.failsafe_status==SBUS_SIGNAL_OK){FailsafeCounter=0;}
+
+
+ sbus.flg_ch_update = false;
+ Output_PWM(pwm);
+}
+
+
+
+
+//pwmをサーボに出力。
+void Output_PWM(int16_t pwm[5])
+{
+ NVIC_DisableIRQ(USART1_IRQn);
+ servo1.pulsewidth_us(pwm[0]);
+ servo2.pulsewidth_us(pwm[1]);
+ servo3.pulsewidth_us(pwm[2]);
+ servo4.pulsewidth_us(pwm[3]);
+ servo5.pulsewidth_us(pwm[4]);
+ servo6.pulsewidth_us(pwm[5]);
+ NVIC_EnableIRQ(USART1_IRQn);
+
+}
+
+void ResetTrim()
+{
+ for(uint8_t i=0; i<6; i++) { //i=4から書き換え_投下サーボは入ってない模様
+ trimpwm[i] = sbus.manualpwm[i];
+ }
+ pc.printf("reset PWM trim\r\n");
+}
+
+
+void SensingMPU()
+{
+ //static int16_t deltaT = 0, t_start = 0;
+ //t_start = t.read_us();
+
+ float rpy[3] = {0}, oldrpy[3] = {0};
+ static uint16_t count_changeRPY = 0;
+ static bool flg_checkoutlier = false;
+ NVIC_DisableIRQ(USART1_IRQn);
+ NVIC_DisableIRQ(USART2_IRQn);
+ NVIC_DisableIRQ(TIM5_IRQn);
+ NVIC_DisableIRQ(EXTI0_IRQn);//MPU割り込み禁止
+ NVIC_DisableIRQ(EXTI9_5_IRQn);//超音波割り込み禁止
+
+ mpu6050.getRollPitchYaw_Skipper(rpy);
+
+ NVIC_EnableIRQ(USART1_IRQn);
+ NVIC_EnableIRQ(USART2_IRQn);
+ NVIC_EnableIRQ(TIM5_IRQn);
+ NVIC_EnableIRQ(EXTI0_IRQn);
+ NVIC_EnableIRQ(EXTI9_5_IRQn);
+
+
+ //外れ値対策
+ for(uint8_t i=0; i<3; i++) rpy[i] *= 180.0f/PI;
+ rpy[ROLL] -= FirstROLL;
+ rpy[PITCH] -= FirstPITCH;
+ rpy[YAW] -= FirstYAW;
+
+ for(uint8_t i=0; i<3; i++) {
+ if(rpy[i] < nowAngle[i]-10 || rpy[i] > nowAngle[i]+10) {
+ flg_checkoutlier = true;
+ }
+ }
+ if(!flg_checkoutlier || count_changeRPY >= 2) {
+ for(uint8_t i=0; i<3; i++) {
+ nowAngle[i] = (rpy[i] + nowAngle[i])/2.0f; //2つの移動平均
+ }
+ count_changeRPY = 0;
+ } else count_changeRPY++;
+ flg_checkoutlier = false;
+
+}
+
+float TranslateNewYaw(float beforeYaw, float newzeroYaw)
+{
+ float newYaw = beforeYaw - newzeroYaw;
+
+ if(newYaw<-180.0f) newYaw += 360.0f;
+ else if(newYaw>180.0f) newYaw -= 360.0f;
+ return newYaw;
+}
+
+
+void getSF_Serial()
+{
+ //NVIC_DisableIRQ(USART1_IRQn);
+ //NVIC_DisableIRQ(EXTI0_IRQn);
+ //NVIC_DisableIRQ(TIM5_IRQn);
+
+
+ static char SFbuf[16]= {'Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q'};
+
+ static int bufcounter=0;
+
+ float targetyaw = 0;
+
+
+
+ if(pc.readable()) { // 受信確認
+
+ SFbuf[bufcounter] = pc.getc(); // 1文字取り出し
+ if(SFbuf[0]!='S') {
+ //pc.printf("x");
+ return;
+ }
+
+
+
+ pc.printf("%c",SFbuf[bufcounter]);
+
+ if(SFbuf[0]=='S'&&bufcounter<5)bufcounter++;
+
+ if(bufcounter==5 && SFbuf[4]=='F') {
+
+ g_landingcommand = SFbuf[1];
+ //pc.printf("%c",g_landingcommand);
+ wait_ms(10);
+ if(g_landingcommand=='Y'){
+ targetyaw = ConvertByteintoFloat(SFbuf[2], SFbuf[3]);
+ if(targetyaw>=0 && targetyaw<=360){
+ g_SerialTargetYAW = ConvertByteintoFloat(SFbuf[2], SFbuf[3]);
+ }
+ }
+ //if(g_landingcommand=='Y')g_SerialTargetYAW =0.0f;
+ bufcounter = 0;
+ memset(SFbuf, 0, sizeof(SFbuf));
+ NVIC_ClearPendingIRQ(USART2_IRQn);
+ //pc.printf("command = %c, commandYAW = %f\r\n", g_landingcommand, g_SerialTargetYAW);
+ }
+
+ else if(bufcounter>=5) {
+ //pc.printf("Communication Falsed.\r\n");
+ memset(SFbuf, 0, sizeof(SFbuf));
+ bufcounter = 0;
+ NVIC_ClearPendingIRQ(USART2_IRQn);
+ }
+ }
+
+ //NVIC_EnableIRQ(TIM5_IRQn);
+ //NVIC_EnableIRQ(EXTI0_IRQn);
+ //NVIC_EnableIRQ(USART1_IRQn);
+}
+
+float ConvertByteintoFloat(char high, char low)
+{
+
+ //int16_t intvalue = (int16_t)high*256 + (int16_t)low;
+ int16_t intvalue = (int16_t)(((int16_t)high << 8) | low); // Turn the MSB and LSB into a signed 16-bit value
+ float floatvalue = (float)intvalue-256;
+ return floatvalue;
+}
+
+
+//超音波割り込み
+
+void UpdateDist()
+{
+ g_distance = usensor.get_dist_cm();
+ usensor.start();
+}
+
+//8の字旋回
+void UpdateTargetAngle_Moebius(float targetAngle[3])
+{
+ static uint8_t RotateCounter=0;
+ static bool flg_setInStartAuto = false;
+ static float FirstYAW_Moebius = 0.0;
+ float newYaw_Moebius;
+
+ if(!flg_setInStartAuto && CheckSW_Up(Ch7)) {
+ FirstYAW_Moebius = nowAngle[YAW];
+ RotateCounter = 0;
+ flg_setInStartAuto = true;
+ } else if(!CheckSW_Up(Ch7)) {
+ flg_setInStartAuto = false;
+ led4 = 0;
+ }
+ autopwm[THR]=oldTHR;
+
+ newYaw_Moebius = TranslateNewYaw(nowAngle[YAW], FirstYAW_Moebius);
+
+ if(RotateCounter == 0 && newYaw_Moebius >90.0 && newYaw_Moebius < 180.0) {
+ RotateCounter++;
+ led4 = 1;
+ pc.printf("Rotate 90\r\n");
+ }
+ if(RotateCounter == 1 && newYaw_Moebius >-180.0 && newYaw_Moebius < -90.0) {
+ RotateCounter++;
+ led4 = 0;
+ pc.printf("Rotate 180\r\n");
+ }
+ if(RotateCounter == 2 && newYaw_Moebius >-90.0 && newYaw_Moebius <-20.0) {
+ RotateCounter++;
+ led4 = 1;
+ pc.printf("Rotate 270\r\n");
+ }
+ if(RotateCounter == 3 && newYaw_Moebius >-10.0 && newYaw_Moebius < 90.0) {
+ RotateCounter++;
+ led4 = 0;
+ pc.printf("Change Rotate direction\r\n");
+ }
+
+
+ if(RotateCounter <= 3) UpdateTargetAngle_Rightloop(targetAngle);
+ else UpdateTargetAngle_Leftloop(targetAngle); //左旋回
+
+}
+
+
+
+//離陸-投下-着陸一連
+void Take_off_and_landing(float targetAngle[3])
+{
+
+ if(!CheckSW_Up(Ch7)) bombing_mode = Takeoff;
+
+ switch(bombing_mode) {
+ case Takeoff:
+ static bool flg_setFirstYaw = false;
+ static int TakeoffCount = 0;
+
+ if(!flg_setFirstYaw && CheckSW_Up(Ch7)) {
+ FirstYAW = nowAngle[YAW];
+ flg_setFirstYaw = true;
+ } else if(flg_setFirstYaw && !CheckSW_Up(Ch7)) {
+ flg_setFirstYaw = false;
+ }
+
+ UpdateTargetAngle_Takeoff(targetAngle);
+ NVIC_DisableIRQ(EXTI9_5_IRQn);
+
+
+ //if(g_distance>120) TakeoffCount++;
+// else TakeoffCount = 0;
+// if(TakeoffCount>3) Chicken_Drop();
+
+ //if(g_distance>180)TakeoffCount++;
+ //else TakeoffCount = 0;
+
+ //if(TakeoffCount>2)Chicken_Drop();
+
+
+ //if(g_distance>210)Chicken_Drop();
+
+
+
+ if(g_distance>120) TakeoffCount++;
+ else TakeoffCount = 0;
+ //Chicken_Drop();
+ NVIC_EnableIRQ(EXTI9_5_IRQn);
+ if(g_landingcommand == 'B'){
+ Chicken_Drop();
+ }
+ if(TakeoffCount>5) {
+
+ //autopwm[THR] = SetTHRinRatio(0.3);
+ autopwm[THR] = 1700;//g_take_off_THROTTLE;//1180+320*2*0.3;
+ targetAngle[PITCH]=g_gostraightPITCH;
+ autopwm[RUD]=1370;//trimpwm[RUD];
+ targetAngle[ROLL]=g_gostraightROLL;
+ Chicken_Drop();
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+ //pc.printf("Now go to Approach mode!!");
+ bombing_mode = Approach;
+ g_landingcommand = 'T';
+ }
+
+
+
+ break;
+
+ //case Chicken:
+ //break;
+ /*
+ case Transition:
+ static int ApproachCount = 0;
+ targetAngle[YAW]=180.0;
+ int Judge = Rotate(targetAngle, g_SerialTargetYAW);
+
+ if(Judge==0) ApproachCount++;
+ if(ApproachCount>5) bombing_mode = Approach;
+ break;
+ */
+ case Approach:
+
+ //autopwm[THR] = SetTHRinRatio(g_loopTHR); //0.7;スロットルの割合
+ autopwm[THR] = minpwm[THR];//1180+320*2*0.3;
+ if(g_Finflag == true){
+ autopwm[THR] = minpwm[THR];
+ autopwm[ELE] = minpwm[ELE];
+ autopwm[RUD]=trimpwm[RUD];
+ autopwm[AIL_R] = minpwm[AIL_R];
+ autopwm[AIL_L]= maxpwm[AIL_L];
+ targetAngle[PITCH] = -80;
+ targetAngle[ROLL] = -80;
+ }else{
+ UpdateTargetAngle_Approach(targetAngle);
+ }
+
+ break;
+
+ default:
+ bombing_mode = Takeoff;
+ break;
+ }
+
+}
+
+//離陸モード
+void UpdateTargetAngle_Takeoff(float targetAngle[3])
+{
+ //pc.printf("%d \r\n",g_distance);
+ static int tELE_start = 0;
+ static bool flg_ELEup = false;
+ int t_def = 0;
+
+ autopwm[RUD] = 1390;//trimpwm[RUD];
+ targetAngle[ROLL]=g_gostraightROLL;
+
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+
+ if(!flg_ELEup && CheckSW_Up(Ch7)) {
+ tELE_start = t.read_ms();
+ flg_ELEup = true;
+ pc.printf("timer start!!!!\r\n");
+ } else if(!CheckSW_Up(Ch7)) {
+ tELE_start = 0;
+ flg_ELEup = false;
+ //pc.printf("lost!!!!\r\n");
+ }
+ if(flg_ELEup) {
+ t_def = t.read_ms() - tELE_start;
+
+ //1.5秒経過すればELE上げ舵へ
+ if(t_def>500) targetAngle[PITCH]= g_take_off_PITCH;
+ else {
+ t_def = 0;
+ targetAngle[PITCH]=g_gostraightPITCH;
+ }
+ }
+ targetAngle[ROLL] = g_gostraightROLL;
+ //targetAngle[PITCH] = g_loopTHR;
+ autopwm[THR] = g_take_off_THROTTLE;//SetTHRinRatio(g_takeoffTHR); //0.7;スロットルの割合
+}
+
+
+//ヨーを目標値にして許容角度になるまで水平旋回
+int Rotate(float targetAngle[3], float TargetYAW)
+{
+ float diffYaw = TranslateNewYaw(TargetYAW, nowAngle[YAW]);
+
+ if(diffYaw > LIMIT_STRAIGHT_YAW) {
+
+ if(diffYaw > THRESHOLD_TURNINGRADIUS_YAW) UpdateTargetAngle_Rightloop_short(targetAngle);
+ else UpdateTargetAngle_Rightloop(targetAngle);
+
+ //UpdateTargetAngle_Rightloop_short(targetAngle);
+ return 1;
+ } else if(diffYaw < -LIMIT_STRAIGHT_YAW) {
+
+ if(diffYaw < -THRESHOLD_TURNINGRADIUS_YAW) UpdateTargetAngle_Leftloop_short(targetAngle);
+ else UpdateTargetAngle_Leftloop(targetAngle);
+
+ //UpdateTargetAngle_Leftloop_short(targetAngle);
+
+ return 1;
+ } else {
+ UpdateTargetAngle_GoStraight(targetAngle);
+ return 0;
+ }
+}
+
+int Rotate_zero(float targetAngle[3], float TargetYAW){
+ float diffYaw = TranslateNewYaw(TargetYAW, nowAngle[YAW]);
+
+ if(diffYaw > LIMIT_STRAIGHT_YAW) {
+
+ /*if(diffYaw > THRESHOLD_TURNINGRADIUS_YAW) UpdateTargetAngle_Rightloop_short(targetAngle);
+ else UpdateTargetAngle_Rightloop(targetAngle);
+ */
+ UpdateTargetAngle_Rightloop_zero(targetAngle);
+ return 1;
+ } else if(diffYaw < -LIMIT_STRAIGHT_YAW) {
+
+ /*if(diffYaw < -THRESHOLD_TURNINGRADIUS_YAW) UpdateTargetAngle_Leftloop_short(targetAngle);
+ else UpdateTargetAngle_Leftloop(targetAngle);
+ */
+ UpdateTargetAngle_Leftloop_zero(targetAngle);
+
+ return 1;
+ } else {
+ UpdateTargetAngle_GoStraight_zero(targetAngle);
+ return 0;
+ }
+}
+
+//チキラー投下
+void Chicken_Drop()
+{
+ //if(CheckSW_Up(Ch7)) {
+ autopwm[DROP] = maxpwm[DROP];
+ //pc.printf("Bombed!\r\n");
+ //RerurnChickenServo1.attach(&ReturnChickenServo1, 3);
+ //operation_mode = Approach;
+ //buzzer = 0;
+ //pc.printf("Goto LeftLoop mode\r\n");
+ //}
+}
+
+void ReturnChickenServo1()
+{
+ autopwm[DROP] = 1344;
+ pc.printf("first reverse\r\n");
+ RerurnChickenServo2.attach(&ReturnChickenServo2, 1);
+}
+
+void ReturnChickenServo2()
+{
+ autopwm[DROP] = 1392;
+ pc.printf("second reverse\r\n");
+}
+
+//着陸モード(PCからの指令に従う)
+void UpdateTargetAngle_Approach(float targetAngle[3])
+{
+
+ static bool Zeroflag=false;//着陸時のスロットル動作確認用
+
+ NVIC_DisableIRQ(USART2_IRQn);
+
+ if(CheckSW_Up(Ch7)) {
+ output_status = Auto;
+ led1 = 1;
+ } else {
+ output_status = Manual;
+ led1 = 0;
+ Zeroflag=true;
+ //g_landingcommand='G';
+ }
+
+ //pc.printf("Zeroflag = %d\r\n",Zeroflag);
+
+ switch(g_landingcommand) {
+ case 'R': //右旋回セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ if(Zeroflag==true){
+ UpdateTargetAngle_Rightloop_zero(targetAngle);
+ }
+ else{
+ UpdateTargetAngle_Rightloop(targetAngle);
+ /*
+ targetAngle[ROLL] = g_rightloopROLL_approach;
+ targetAngle[PITCH] = g_rightloopPITCH_approach ;
+ autopwm[RUD]=g_rightloopRUD_approach; //RUD固定
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
+ }
+ else {autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+ autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
+ */
+ }
+
+ break;
+
+ case 'L': //左旋回セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ if(Zeroflag==true){
+ UpdateTargetAngle_Leftloop_zero(targetAngle);
+ }else{
+ UpdateTargetAngle_Leftloop(targetAngle);
+ /*targetAngle[ROLL] = g_leftloopROLL_approach;
+ targetAngle[PITCH] = g_leftloopPITCH_approach;
+ autopwm[RUD]=g_leftloopRUD_approach;
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+ */
+ }
+
+ break;
+
+ case 'G': //直進セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ if(Zeroflag==true){
+ UpdateTargetAngle_GoStraight_zero(targetAngle);
+ }
+ else{
+ UpdateTargetAngle_GoStraight(targetAngle);
+ /*
+ targetAngle[ROLL] = g_gostraightROLL;
+ targetAngle[PITCH] = g_gostraightPITCH;
+ */
+ }
+
+ break;
+
+ case 'Y': //指定ノヨー方向ニ移動セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ if(Zeroflag==true){
+ Rotate_zero(targetAngle, g_SerialTargetYAW);
+ //autopwm[THR]=minpwm[THR];
+ }else{
+ Rotate(targetAngle, g_SerialTargetYAW);
+ //autopwm[THR]=SetTHRinRatio(g_loopTHR+0.05);
+ }
+ break;
+
+ case 'T': //0度ノヨー方向ニ移動セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ if(Zeroflag==true){
+ Rotate_zero(targetAngle, 0);
+ //autopwm[THR]=minpwm[THR];
+ }else{
+ Rotate(targetAngle, 0);
+ //autopwm[THR]=SetTHRinRatio(g_loopTHR+0.05);
+ }
+ break;
+
+ case 'U': //機首ヲ上ゲヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ static int UpCounter=0;
+ UpCounter++;
+ if(UpCounter==3) {
+ g_Finflag = true;
+ }
+
+ break;
+
+ case 'Z': //ヤレバワカル
+ NVIC_EnableIRQ(USART2_IRQn);
+ autopwm[THR] = minpwm[THR];
+ autopwm[ELE] = minpwm[ELE];
+ autopwm[RUD]=trimpwm[RUD];
+ autopwm[AIL_R] = minpwm[AIL_R];
+ autopwm[AIL_L]= maxpwm[AIL_L];
+ targetAngle[ROLL] = -80;
+
+ break;
+
+ /*case 'B': //ブザーヲ鳴ラセ
+ //buzzer = 1;
+ NVIC_EnableIRQ(USART2_IRQn);
+ break;*/
+
+ case 'B': //物資ヲ落トセ
+ NVIC_EnableIRQ(USART2_IRQn);
+ Chicken_Drop();
+ if(Zeroflag==true){
+ Rotate_zero(targetAngle, 0);
+ //autopwm[THR]=minpwm[THR];
+ }else{
+ Rotate(targetAngle, 0);
+ //autopwm[THR]=SetTHRinRatio(g_loopTHR+0.05);
+ }
+
+ break;
+
+ case 'C': //停止セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ /*targetAngle[ROLL] = g_gostraightROLL;
+ targetAngle[PITCH] = g_gostraightPITCH;
+ autopwm[THR] = minpwm[THR];
+ */
+ Zeroflag = true;
+ if(Zeroflag==true){
+ Rotate_zero(targetAngle, 0);
+ //autopwm[THR]=minpwm[THR];
+ }else{
+ Rotate(targetAngle, 0);
+ //autopwm[THR]=SetTHRinRatio(g_loopTHR+0.05);
+ }
+
+ break;
+
+ case 'X': //再起動セヨ
+ NVIC_EnableIRQ(USART2_IRQn);
+ /*
+ targetAngle[ROLL] = g_gostraightROLL;
+ targetAngle[PITCH] = g_gostraightPITCH;
+ autopwm[THR] = minpwm[THR];
+ */
+ Zeroflag = false;
+ if(Zeroflag==true){
+ Rotate_zero(targetAngle, 0);
+ //autopwm[THR]=minpwm[THR];
+ }else{
+ Rotate(targetAngle, 0);
+ //autopwm[THR]=SetTHRinRatio(g_loopTHR+0.05);
+ }
+
+ break;
+
+ default :
+ NVIC_EnableIRQ(USART2_IRQn);
+ break;
+
+
+ }
+
+}
+
+void checkHeight(float targetAngle[3])
+{
+
+ static int targetHeight = 200;
+
+ NVIC_DisableIRQ(EXTI9_5_IRQn);
+ if(g_distance < targetHeight + ALLOWHEIGHT) {
+ UpdateTargetAngle_NoseUP(targetAngle);
+ if(CheckSW_Up(Ch7)) led2 = 1;
+ } else if(g_distance > targetHeight - ALLOWHEIGHT) {
+ UpdateTargetAngle_NoseDOWN(targetAngle);
+ if(CheckSW_Up(Ch7)) led2 = 1;
+ } else led2=0;
+ NVIC_EnableIRQ(EXTI9_5_IRQn);
+}
+
+void UpdateTargetAngle_NoseUP(float targetAngle[3])
+{
+
+ //targetAngle[PITCH] += 2.0f;
+ //if(nowAngle[PITCH]<targetAngle[PITCH]) autopwm[THR] = SetTHRinRatio(0.6);
+ autopwm[THR] = SetTHRinRatio(g_loopTHR+0.05);
+ //pc.printf("nose UP");
+}
+
+void UpdateTargetAngle_NoseDOWN(float targetAngle[3])
+{
+
+ //targetAngle[PITCH] -= 2.0f;
+ autopwm[THR] = SetTHRinRatio(g_loopTHR-0.05);
+ //pc.printf("nose DOWN");
+}
+
+//直進
+void UpdateTargetAngle_GoStraight(float targetAngle[3])
+{
+
+ autopwm[RUD] = trimpwm[RUD];
+ targetAngle[ROLL] = g_gostraightROLL;
+ targetAngle[PITCH] = g_gostraightPITCH;
+ autopwm[THR] = SetTHRinRatio(g_loopTHR);
+
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+ autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
+
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+//直進(着陸時スロットル0のとき)
+void UpdateTargetAngle_GoStraight_zero(float targetAngle[3])
+{
+
+ autopwm[RUD] = trimpwm[RUD];
+ targetAngle[ROLL] = g_gostraightROLL;
+ targetAngle[PITCH] = -7.0;//g_gostraightPITCH;
+ autopwm[THR] = minpwm[THR];
+
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+//右旋回
+void UpdateTargetAngle_Rightloop(float targetAngle[3]) //右旋回
+{
+ targetAngle[ROLL] = g_rightloopROLL;
+ targetAngle[PITCH] = g_rightloopPITCH;
+ autopwm[RUD]=g_rightloopRUD; //RUD固定
+ autopwm[THR] = SetTHRinRatio(g_rightloop_THR_rate); //手動スロットル記憶
+
+ /*
+ if (nowAngle[ROLL]>20.0||nowAngle[ROLL]<-20.0){
+ t2.start();
+ pc.printf("Timer start.");
+ }
+ if(0.0<t2.read()<5.0){
+ //pc.printf("tagetAngle is changed.");
+ targetAngle[ROLL] = rightloopROLL2;
+ }
+ else {
+ t2.stop();
+ t2.reset();
+ pc.printf("Timer stopped.");
+ targetAngle[ROLL] = g_rightloopROLL;
+ }
+ */
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+ autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
+
+
+ //checkHeight(targetAngle);
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+void UpdateTargetAngle_Rightloop_UP(float targetAngle[3]) //右上昇旋回
+{
+ //autopwm[ELE]=maxpwm[ELE];
+ targetAngle[ROLL] = g_ascending_ROLL;
+ targetAngle[PITCH] = g_ascendingPITCH;
+ autopwm[RUD]=g_ascending_RUD; //RUD固定
+ autopwm[THR] = SetTHRinRatio(g_ascending_THR_rate); //手動スロットル記憶
+
+ /*
+ if (nowAngle[ROLL]>20.0||nowAngle[ROLL]<-20.0){
+ t2.start();
+ pc.printf("Timer start.");
+ }
+ if(0.0<t2.read()<5.0){
+ //pc.printf("tagetAngle is changed.");
+ targetAngle[ROLL] = rightloopROLL2;
+ }
+ else {
+ t2.stop();
+ t2.reset();
+ pc.printf("Timer stopped.");
+ targetAngle[ROLL] = g_rightloopROLL;
+ }
+ */
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+ autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
+
+
+ //checkHeight(targetAngle);
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+//右旋回(着陸時スロットル0の時)
+void UpdateTargetAngle_Rightloop_zero(float targetAngle[3]) //右旋回
+{
+ autopwm[THR]=minpwm[THR];
+ targetAngle[ROLL] = g_rightloopROLL_approach;
+ targetAngle[PITCH] = g_rightloopPITCH_approach ;
+ autopwm[RUD]=g_rightloopRUD_approach; //RUD固定
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){ //エルロン上がりやすさ調節
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising; //エルロンサーボ二つ使用時
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
+
+ autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
+
+ //checkHeight(targetAngle);
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+void UpdateTargetAngle_Rightloop_short(float targetAngle[3]) //右旋回
+{
+
+ targetAngle[ROLL] = g_rightloopROLLshort;
+ targetAngle[PITCH] = g_rightloopPITCHshort;
+ autopwm[RUD]=g_rightloopshortRUD;
+ autopwm[THR] = SetTHRinRatio(g_rightloop_THR_rate);
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent; //エルロンサーボ二つ使用時
+
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+
+//左旋回
+void UpdateTargetAngle_Leftloop(float targetAngle[3])
+{
+
+ targetAngle[ROLL] = g_leftloopROLL;
+ targetAngle[PITCH] = g_leftloopPITCH;
+ //autopwm[ELE] = 1700;
+ autopwm[RUD]=g_leftloopRUD;
+ autopwm[THR] = SetTHRinRatio(g_leftloop_THR_rate);
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){
+ autopwm[AIL_L]=trimpwm[AIL_L]+g_AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+g_AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent; //エルロンサーボ二つ使用時
+
+ //checkHeight(targetAngle);
+
+ //printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[], targetAngle[PITCH], autopwm[THR]);
+}
+
+//左旋回(着陸時スロットル0のとき)
+void UpdateTargetAngle_Leftloop_zero(float targetAngle[3])
+{
+
+ targetAngle[ROLL] = g_leftloopROLL_approach;
+ targetAngle[PITCH] = g_leftloopPITCH_approach;
+ autopwm[RUD]=g_leftloopRUD_approach;
+ autopwm[THR] = minpwm[THR];
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent; //エルロンサーボ二つ使用時
+
+ //autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_Ratio_leftloop;
+ //checkHeight(targetAngle);
+
+ //printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[], targetAngle[PITCH], autopwm[THR]);
+}
+
+void UpdateTargetAngle_Leftloop_short(float targetAngle[3])
+{
+
+ targetAngle[ROLL] = g_leftloopROLLshort;
+ targetAngle[PITCH] = g_leftloopPITCHshort;
+ autopwm[RUD]=g_leftloopRUD;
+ autopwm[THR] = SetTHRinRatio(g_leftloop_THR_rate);
+ if(autopwm[AIL_R]<trimpwm[AIL_R]){
+ autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
+ }
+ else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent; //エルロンサーボ二つ使用時
+
+ //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
+}
+
+void Ascending(float targetAngle[3]){
+ static uint8_t RotateCounter=0;
+ static bool LapCounter = false;
+ static bool UpFlag = false;
+ static bool PressFlag = false;
+ static float FirstHeight = 0;
+ static bool flg_setInStartAuto = false;
+ //static float Time = 0.0;
+ static float FirstYaw_Ascending = 0;
+ float newYaw_Ascending;
+
+ //pc.printf("FirstHeight = %f g_z_comp = %f g_AscendingFlag = %d\r\n",FirstHeight,g_z_comp,g_AscendingFlag);
+
+ getBMP280();
+
+ if(!flg_setInStartAuto && CheckSW_Up(Ch7)) {
+ FirstYaw_Ascending = nowAngle[YAW];
+ RotateCounter = 0;
+ flg_setInStartAuto = true;
+ LapCounter = false;
+ UpFlag = false;
+ PressFlag = false;
+ //tBMP.reset();
+ } else if(!CheckSW_Up(Ch7)) {
+ flg_setInStartAuto = false;
+ led4 = 0;
+ }
+
+ newYaw_Ascending = TranslateNewYaw(nowAngle[YAW], FirstYaw_Ascending);
+
+ if(RotateCounter == 0 && newYaw_Ascending >90.0 && newYaw_Ascending < 180.0) {
+ RotateCounter++;
+ led4 = 1;
+ pc.printf("Rotate 90\r\n");
+ }
+ if(RotateCounter == 1 && newYaw_Ascending >-180.0 && newYaw_Ascending < -90.0) {
+ RotateCounter++;
+ led4 = 0;
+ pc.printf("Rotate 180\r\n");
+ }
+ if(RotateCounter == 2 && newYaw_Ascending >-90.0 && newYaw_Ascending <-20.0) {
+ RotateCounter++;
+ led4 = 1;
+ pc.printf("Rotate 270\r\n");
+ }
+ if(RotateCounter == 3 && newYaw_Ascending >-10.0 && newYaw_Ascending < 90.0) {
+ RotateCounter++;
+ led4 = 0;
+ if(LapCounter == false){
+ RotateCounter = 0;
+ LapCounter = true;
+ pc.printf("Lap2\r\n");
+ }
+ }
+
+ if(RotateCounter <= 3){
+ UpdateTargetAngle_Rightloop(targetAngle);
+ }else if(3 < RotateCounter && UpFlag == false){
+ if(PressFlag == false){
+ FirstHeight = g_z_comp;
+ //tBMP.start();
+ PressFlag = true;
+ led4 = 1;
+ }
+ //Time = tBMP.read();
+ if(g_z_comp > FirstHeight+3000){
+ UpFlag = true;
+ led4 = 0;
+ }
+ UpdateTargetAngle_Rightloop_UP(targetAngle);
+ }else{
+ UpdateTargetAngle_Rightloop(targetAngle);
+ }
+
+
+}
+
+void Sbusprintf()
+{
+
+ for(uint8_t i=0; i<8; i++) pc.printf("ch.%d = %d ",i+1,sbus.manualpwm[i]);
+ pc.printf("\r\n");
+
+}
+
+
+//---sensing---
+//センサーの値を読み込み、各種フィルタをかける(認知)
+void sensing()
+{
+ // If intPin goes high, all data registers have new data
+ if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
+
+ mpu9250.readAccelData(accelCount); // Read the x/y/z adc values
+ // Now we'll calculate the accleration value into actual g's
+ ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
+ ay = (float)accelCount[1]*aRes - accelBias[1];
+ az = (float)accelCount[2]*aRes - accelBias[2];
+
+ mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values
+ // Calculate the gyro value into actual degrees per second
+ gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set
+ gy = (float)gyroCount[1]*gRes - gyroBias[1];
+ gz = (float)gyroCount[2]*gRes - gyroBias[2];
+
+ mpu9250.readMagData(magCount); // Read the x/y/z adc values
+ // Calculate the magnetometer values in milliGauss
+ // Include factory calibration per data sheet and user environmental corrections
+ mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set
+ my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];
+ mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];
+ }
+
+ Now = t.read_us();
+ deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
+ lastUpdate = Now;
+
+ g_sum += deltat;
+ g_sumCount++;
+
+// if(lastUpdate - firstUpdate > 10000000.0f) {
+// beta = 0.04; // decrease filter gain after stabilized
+// zeta = 0.015; // increasey bias drift gain after stabilized
+// }
+
+ // Pass gyro rate as rad/s
+ mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz);
+ // mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
+
+ mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz);
+ // mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
+
+ /* Auto_Loop()で50ms待ってるから要らないと思う
+ // Serial print and/or display at 0.5 s rate independent of data rates
+ delt_t = t.read_ms() - count;
+ if (delt_t > 500) { // update LCD once per half-second independent of read rate
+ */
+
+ //pc.printf("ax = %f", 1000*ax);
+ //pc.printf(" ay = %f", 1000*ay);
+ //pc.printf(" az = %f mg\n\r", 1000*az);
+
+ //pc.printf("gx = %f", gx);
+ //pc.printf(" gy = %f", gy);
+ //pc.printf(" gz = %f deg/s\n\r", gz);
+
+ //pc.printf("mx = %f,", mx);
+ //pc.printf(" my = %f,", my);
+ //pc.printf(" mz = %f mG\n\r", mz);
+
+ tempCount = mpu9250.readTempData(); // Read the adc values
+ temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
+ //pc.printf(" temperature = %f C\n\r", temperature);
+
+ //pc.printf("q0 = %f\n\r", q[0]);
+ //pc.printf("q1 = %f\n\r", q[1]);
+ //pc.printf("q2 = %f\n\r", q[2]);
+ //pc.printf("q3 = %f\n\r", q[3]);
+
+
+ // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
+ // In this coordinate system, the positive z-axis is down toward Earth.
+ // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise.
+ // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
+ // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
+ // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
+ // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
+ // applied in the correct order which for this configuration is yaw, pitch, and then roll.
+ // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
+ yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
+ roll = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
+ pitch = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
+ pitch *= 180.0f / PI;
+ yaw *= 180.0f / PI;
+ yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
+ roll *= 180.0f / PI;
+
+ //pc.printf("$%d %d %d;",(int)(yaw*100),(int)(pitch*100),(int)(roll*100));
+ //pc.printf("Yaw: %f Pitch:%f Roll:%f\n\r", yaw, pitch, roll);
+ //pc.printf("average rate = %f\n\r", (float) sumCount/sum);
+
+ count = t.read_ms();
+ g_sum = 0;
+ g_sumCount = 0;
+ //}
+}
+
+void SetupBMP280(){
+ bmp.initialize(BMP280::INDOOR_NAVIGATION);
+
+ for(int sn = 0; sn < 100; sn++){
+ g_press = bmp.getPressure();
+ if(sn > 0){
+ g_InitPress[sn] = g_press;
+ g_InitPressAve += g_InitPress[sn];
+ float press_ratio = g_st_press / g_press;
+ g_InitBMPHeight[sn] = ((powf(press_ratio, 0.19) - 1) * 298.15 * 1000) / 0.0065;
+ g_InitBMPHeightAve += g_InitBMPHeight[sn];
+
+ }
+ pc.printf("%f,%f\r\n", g_InitBMPHeight[sn],g_InitPress[sn]);
+ wait(0.05);
+ }
+
+ g_InitPressAve /= 100.0;
+
+ g_InitBMPHeightAve /= 100.0;
+
+ pc.printf("\r\n%f,%f\r\n\r\n", g_InitBMPHeightAve,g_InitPressAve);
+
+ pc.printf("bmp280 initialized\r\n");
+
+ g_BMPheight = g_InitBMPHeightAve;
+
+ tBMP.start();//dtを計測
+
+ sensing();//最初だけ空回し
+
+ g_tempaz[0] = az * g_grav * 1000;
+
+}
+
+void getBMP280(){
+ float z_angle, gyro_ver, z_angle_prev;
+ static float press_rel_coef = 0.03;
+ float press_ratio = g_st_press / g_press;
+
+ g_z_PressHeight = g_BMPheight;
+
+ z_angle = atan2(sqrt(ax * ax + ay * ay), az);
+ gyro_ver = cos(z_angle); //垂直方向の加速度
+
+ g_dt = tBMP.read_us();
+ g_dt /= 1000000;
+ tBMP.reset();
+ tBMP.start();
+
+
+ g_z_AccelHeight = g_z_prev - g_v_prev * g_dt - (az - gyro_ver) * g_grav *1000* g_dt * g_dt / 2;
+
+ g_z_comp = g_z_PressHeight* press_rel_coef + g_z_AccelHeight* (1 - press_rel_coef);//係数は足して1になるように適当に設定,単位はmm
+
+ //pc.printf("%f\r\n",g_z_comp/1000);
+
+ g_BMPheight_int = g_z_comp;
+
+ g_press = bmp.getPressure();
+
+ g_BMPheight = ((powf(press_ratio, 0.19) - 1) * 298.15 *1000) / 0.0065 - g_InitBMPHeightAve;
+
+ NVIC_DisableIRQ(USART1_IRQn);
+ NVIC_DisableIRQ(USART2_IRQn);
+ NVIC_DisableIRQ(TIM5_IRQn);
+ NVIC_DisableIRQ(EXTI0_IRQn);//MPU割り込み禁止
+ NVIC_DisableIRQ(EXTI9_5_IRQn);//超音波割り込み禁止
+ sensing();
+ NVIC_EnableIRQ(USART1_IRQn);
+ NVIC_EnableIRQ(USART2_IRQn);
+ NVIC_EnableIRQ(TIM5_IRQn);
+ NVIC_EnableIRQ(EXTI0_IRQn);
+ NVIC_EnableIRQ(EXTI9_5_IRQn);
+
+ g_v_prev = (g_z_comp - g_z_prev) / g_dt / 1000000;
+
+ g_z_prev = g_z_comp;
+
+
+ //wait_ms(1.0);
+
+}
+
+
+
+//デバッグ用=
+void DebugPrint()
+{
+ /*
+ static int16_t deltaT = 0, t_start = 0;
+ //deltaT = t.read_u2s() - t_start;
+ pc.printf("t:%d us, ",deltaT);
+ pc.printf("\r\n");
+ t_start = t.read_us();
+
+ for(uint8_t i=0; i<6; i++) pc.printf("sbus.manualpwm[%d]:%d ",i,sbus.manualpwm[i]);
+ if(g_trim_check){
+ for(uint8_t i=0; i<6; i++) pc.printf("sbus.manualpwm[%d]:%d ",i,sbus.manualpwm[i]);
+ pc.printf("\r\n");
+ }
+
+ pc.printf("trimpwm[AIL_R]:%d ELE:%d THR:%d RUD:%d 4:%d AIL_L:%d",trimpwm[AIL_R],trimpwm[ELE],trimpwm[THR],trimpwm[RUD],trimpwm[4],trimpwm[AIL_L]);
+ for(uint8_t i=0; i<8; i++) pc.printf("sbus.manualpwm[%d]:%d ",i,sbus.manualpwm[i]);
+ for(uint8_t i=1; i<4; i++) pc.printf("sbus.manualpwm[%d]:%d ",i,sbus.manualpwm[i]);
+ pc.printf("\r\n");
+ for(uint8_t i=0; i<3; i++) pc.printf("nowangle[%d]:%3.2f\t",i,nowAngle[i]);
+ for(uint8_t i=0; i<2; i++) pc.printf("nowangle[%d]:%3.2f\t",i,nowAngle[i]); //ロール、ピッチのみ 小数点以下2ケタ
+ pc.printf("nowangle[pitch]:%3.2f\t\r\n",nowAngle[2]);
+ pc.printf("autopwm[ELE]:%d\t\r\n",autopwm[ELE]);
+ pc.printf("autpwm[RUD]:%d\t",autopwm[RUD]);*/
+ NVIC_DisableIRQ(EXTI9_5_IRQn);
+ pc.printf("g_distance:%d\t",g_distance);/*
+ NVIC_EnableIRQ(EXTI9_5_IRQn);
+ pc.printf("Mode: %c: ",g_buf[0]);
+ if(g_buf[0] == 'Y') pc.printf(" %3.1f",g_SerialTargetYAW);
+ pc.printf("%f",g_z_comp);
+ pc.printf("\r\n%f,%f\r\n", g_InitBMPHeightAve,g_InitPressAve);
+ pc.printf("\r\n"); */
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Tue Sep 13 03:12:26 2022 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/mbed_official/code/mbed/builds/65be27845400 \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/pid/pid.cpp Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,73 @@
+#include "mbed.h"
+#include "pid.h"
+
+
+PID::PID(void){
+ initialize();
+}
+
+PID::PID(double Pgain, double Igain, double Dgain){
+ initialize();
+ setPIDgain(Pgain,Igain,Dgain);
+}
+
+PID::PID(double Pgain, double Igain, double Dgain, double Max, double Min){
+ initialize();
+ setPIDgain(Pgain,Igain,Dgain);
+ setMaxMin(Max,Min);
+}
+
+PID::~PID(){
+
+}
+
+void PID::initialize(void){
+ kp = 0.0; ki = 0.0; kd = 0.0;
+ max = 0.0; min = 0.0;
+ dt = 0.0;
+ integral = 0.0;
+ for(uint8_t i=0; i<2; i++){
+ oldval[i] = 0.0;
+ diff[i] = 0.0;
+ }
+ maxcheck = false;
+ mincheck = false;
+}
+
+void PID::setPIDgain(double Pgain, double Igain, double Dgain){
+ kp = Pgain;
+ ki = Igain;
+ kd = Dgain;
+}
+
+void PID::setMaxMin(double Max, double Min){
+ if(Max < Min) return; //最大値<最小値であれば設定せずに終了
+ max = Max;
+ min = Min;
+ maxcheck = true; mincheck = true;
+}
+
+void PID::switchMaxMin(bool Maxcheck, bool Mincheck){
+ maxcheck = Maxcheck;
+ mincheck = Mincheck;
+}
+
+double PID::calcPID(double nowval, double targetval, double dt){
+ double p,i,d,pid;
+
+ diff[1] = diff[0];
+ diff[0] = nowval - targetval;
+ if(diff[1] == 0.0) return 0.0; //前回の値がない場合,0.0を返す
+
+ integral += (diff[0] + diff[1]) / 2.0 * dt;
+
+ p = kp * diff[0];
+ i = ki * integral;
+ d = kd * (diff[0] - diff[1]) / dt;
+ pid = p + i + d;
+ if(maxcheck && pid>max) pid = max;
+ if(mincheck && pid<min) pid = min;
+
+ return pid;
+
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/pid/pid.h Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,32 @@
+#ifndef PID_MBED_H
+#define PID_MBED_H
+
+
+#include "mbed.h"
+
+class PID
+{
+public:
+ double kp, ki, kd, max, min, dt;
+
+ //コンストラクタ
+ PID();
+ PID(double Pgain, double Igain, double Dgain);
+ PID(double Pgain, double Igain, double Dgain, double Max, double Min);
+ //デストラクタ
+ ~PID();
+
+ void initialize(void);
+ void setPIDgain(double Pgain, double Igain, double Dgain);
+ void setMaxMin(double Max, double Min);
+ void switchMaxMin(bool Maxcheck, bool Mincheck);
+ double calcPID(double nowval, double targetval, double dt);
+
+
+private:
+ double integral;
+ double oldval[2], diff[2];
+ bool maxcheck, mincheck;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/sbus/sbus.cpp Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,124 @@
+#include "mbed.h"
+#include "sbus.h"
+
+
+SBUS::SBUS(PinName tx, PinName rx)
+ :
+ rawserial_p(new RawSerial(tx,rx)),
+ rawserial(*rawserial_p)
+{}
+
+SBUS::~SBUS()
+{
+ if(rawserial_p != NULL) delete rawserial_p;
+}
+
+void SBUS::initialize(void){
+ flg_ch_update = false;
+ failsafe_status = SBUS_SIGNAL_FAILSAFE;
+ cnt_sbus = 0;
+ lastfunc = NULL;
+ for (uint8_t i = 0; i < 25; i++) buf_sbus[i] = 0;
+
+ rawserial.baud(100000);
+ rawserial.format(8, Serial::Even, 2);
+}
+
+void SBUS::startInterrupt(void){
+ rawserial.attach(this, &SBUS::func_interrupt, RawSerial::RxIrq); //fromSBUStoPWMの前に&が必要?
+}
+
+//SBUS::stopInterrupt(void){
+//}
+
+void SBUS::setLastfuncPoint(void (*func_p)(void)){
+ lastfunc = func_p;
+}
+
+//シリアル割り込みで実行する関数
+void SBUS::func_interrupt(void){
+ if(catchSerial()){
+ unpackSerialdata();
+ inputPwm();
+ if(lastfunc != NULL) (*lastfunc)(); //setLastfuncPointで設定した関数を最後に実行
+ }
+ return;
+}
+
+int8_t SBUS::catchSerial(void){
+ buf_sbus[cnt_sbus] = rawserial.getc();
+ if(buf_sbus[0] == 0x0f) cnt_sbus ++;
+ if(cnt_sbus >=25){
+ if(buf_sbus[24] == 0x00){
+ return(1); //calculatePwm実行
+ }else{
+ cnt_sbus = 0;
+ }
+ }
+ return(0);
+}
+
+void SBUS::unpackSerialdata(void){
+/* for (uint8_t i=0; i<25; i++){
+ pc.printf("%x ", buf_sbus[i]);
+ }pc.printf("\n");
+*/
+ // clear channels[]
+ for (uint8_t i=0; i<18; i++) {channels[i] = 0;}
+
+ // reset counters
+ byte_in_sbus = 1;
+ bit_in_sbus = 0;
+ ch = 0;
+ bit_in_channel = 0;
+
+ // process actual sbus data
+ for (uint8_t i=0; i<176; i++) {
+ if (buf_sbus[byte_in_sbus] & (1<<bit_in_sbus)) {
+ channels[ch] |= (1<<bit_in_channel);
+ }
+ bit_in_sbus++;
+ bit_in_channel++;
+
+ if (bit_in_sbus == 8) {
+ bit_in_sbus =0;
+ byte_in_sbus++;
+ }
+ if (bit_in_channel == 11) {
+ bit_in_channel =0;
+ ch++;
+ }
+ }
+ // DigiChannel 1
+ if (buf_sbus[23] & (1<<0)) {
+ channels[16] = 1;
+ }else{
+ channels[16] = 0;
+ }
+ // DigiChannel 2
+ if (buf_sbus[23] & (1<<1)) {
+ channels[17] = 1;
+ }else{
+ channels[17] = 0;
+ }
+ // Failsafe
+ failsafe_status = SBUS_SIGNAL_OK;
+ if (buf_sbus[23] & (1<<2)) {
+ failsafe_status = SBUS_SIGNAL_LOST;
+ }
+ if (buf_sbus[23] & (1<<3)) {
+ failsafe_status = SBUS_SIGNAL_FAILSAFE;
+ }
+ //channels[i] = channels[i]>>1;
+ for (uint8_t i=0; i<25; i++) {buf_sbus[i] = 0;}
+ cnt_sbus = 0;
+ flg_ch_update = true;
+
+ return;
+}
+
+void SBUS::inputPwm(void){
+ for(uint8_t i=0; i<8; i++){
+ manualpwm[i] = (channels[i]>>1) + 1000;
+ }
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/sbus/sbus.h Tue Sep 13 03:12:26 2022 +0000
@@ -0,0 +1,52 @@
+#ifndef MBED_SUBS_H
+#define MBED_SUBS_H
+
+
+#include "mbed.h"
+
+#define SBUS_SIGNAL_OK 0x00
+#define SBUS_SIGNAL_LOST 0x01
+#define SBUS_SIGNAL_FAILSAFE 0x03
+
+typedef void (*V_FUNC_V)(void);
+
+class SBUS
+{
+public:
+ uint16_t manualpwm[8]; //pwmの数値 1000~2000で表記 main文ではこの変数を使う
+ uint8_t failsafe_status;
+ bool flg_ch_update;
+
+ //コンストラクタ
+ SBUS();
+ SBUS(PinName tx, PinName rx);
+ //デストラクタ
+ virtual ~SBUS(); //この場合virtualをつける必要はなさそうだが参考プログラムについてたため一応入れる
+
+ void initialize(void); //初期化
+ void startInterrupt(void); //シリアル割り込み開始
+ //void stopInterrupt(void);
+ void setLastfuncPoint(void (*func)(void)); //割り込み処理実行後に行う関数を設定 PWM出力用
+
+
+private:
+ RawSerial *rawserial_p;
+ RawSerial &rawserial;
+
+ volatile uint8_t buf_sbus[25];
+ volatile int cnt_sbus;
+ uint8_t byte_in_sbus;
+ uint8_t bit_in_sbus;
+ uint8_t ch;
+ uint8_t bit_in_channel;
+ int16_t channels[18]; //元はstatic int16_t channels[18];
+ V_FUNC_V lastfunc;
+
+ void func_interrupt(void); //シリアル割り込みで実行する関数
+ int8_t catchSerial(void); //シリアルデータを取得
+ void unpackSerialdata(void); //シリアルデータから各チャンネルの情報を取得
+ void inputPwm(void); //manualpwm変数に値を入力
+};
+
+
+#endif
\ No newline at end of file