mirror of https://github.com/ArduPilot/ardupilot
Fixed merge issues
This commit is contained in:
parent
a40a026220
commit
f2d6708058
|
@ -540,7 +540,7 @@ Vector3f accels_rot;
|
||||||
|
|
||||||
// this is just me playing with the sensors
|
// this is just me playing with the sensors
|
||||||
// the 2 code is not functioning and you should try 1 instead
|
// the 2 code is not functioning and you should try 1 instead
|
||||||
#elif ACCEL_ALT_HOLD == 2
|
#if ACCEL_ALT_HOLD == 2
|
||||||
static float Z_integrator;
|
static float Z_integrator;
|
||||||
static float Z_gain = 3;
|
static float Z_gain = 3;
|
||||||
static float Z_offset = 0;
|
static float Z_offset = 0;
|
||||||
|
|
|
@ -684,6 +684,7 @@ static void Log_Read_Motors()
|
||||||
// Write an optical flow packet. Total length : 18 bytes
|
// Write an optical flow packet. Total length : 18 bytes
|
||||||
static void Log_Write_Optflow()
|
static void Log_Write_Optflow()
|
||||||
{
|
{
|
||||||
|
#ifdef OPTFLOW_ENABLED
|
||||||
DataFlash.WriteByte(HEAD_BYTE1);
|
DataFlash.WriteByte(HEAD_BYTE1);
|
||||||
DataFlash.WriteByte(HEAD_BYTE2);
|
DataFlash.WriteByte(HEAD_BYTE2);
|
||||||
DataFlash.WriteByte(LOG_OPTFLOW_MSG);
|
DataFlash.WriteByte(LOG_OPTFLOW_MSG);
|
||||||
|
@ -700,6 +701,7 @@ static void Log_Write_Optflow()
|
||||||
|
|
||||||
static void Log_Read_Optflow()
|
static void Log_Read_Optflow()
|
||||||
{
|
{
|
||||||
|
#ifdef OPTFLOW_ENABLED
|
||||||
int16_t temp1 = DataFlash.ReadInt(); // 1
|
int16_t temp1 = DataFlash.ReadInt(); // 1
|
||||||
int16_t temp2 = DataFlash.ReadInt(); // 2
|
int16_t temp2 = DataFlash.ReadInt(); // 2
|
||||||
int16_t temp3 = DataFlash.ReadInt(); // 3
|
int16_t temp3 = DataFlash.ReadInt(); // 3
|
||||||
|
@ -712,6 +714,7 @@ static void Log_Read_Optflow()
|
||||||
temp3,
|
temp3,
|
||||||
temp4,
|
temp4,
|
||||||
temp5);
|
temp5);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void Log_Write_Nav_Tuning()
|
static void Log_Write_Nav_Tuning()
|
||||||
|
|
Loading…
Reference in New Issue