Merge remote-tracking branch 'refs/remotes/origin/master' into Compass
This commit is contained in:
commit
b4d689c434
@ -170,7 +170,7 @@ void getCurrentValues(float sensorValues[3], uint8_t ID_profile)
|
|||||||
sensorValues[PITCH] = accelProfile.pitchAngle + accPitchFineTune;
|
sensorValues[PITCH] = accelProfile.pitchAngle + accPitchFineTune;
|
||||||
|
|
||||||
/*Checks the biggest angle */
|
/*Checks the biggest angle */
|
||||||
throttleRate = (ABS_FLOAT(sensorValues[ROLL]) > ABS_FLOAT(sensorValues[PITCH]) )? 2 - cos(sensorValues[ROLL]*M_PI/180) : 2 - cos(sensorValues[PITCH]*M_PI/180);
|
throttleRate = cos(ABS_FLOAT(sensorValues[PITCH])*M_PI/180)*cos(ABS_FLOAT(sensorValues[ROLL])*M_PI/180);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case PID_ID_BAROMETER:
|
case PID_ID_BAROMETER:
|
||||||
|
@ -103,10 +103,12 @@ void mix()
|
|||||||
int16_t RPY_Mix[MOTOR_COUNT]; // Roll Pitch and Yaw variables array
|
int16_t RPY_Mix[MOTOR_COUNT]; // Roll Pitch and Yaw variables array
|
||||||
int16_t RPY_Mix_Min = 0; // Stores the minimum desired command for any motor
|
int16_t RPY_Mix_Min = 0; // Stores the minimum desired command for any motor
|
||||||
int16_t RPY_Mix_Max = 0; // Maximum desired command for any motor
|
int16_t RPY_Mix_Max = 0; // Maximum desired command for any motor
|
||||||
int16_t throttle = PidProfile[PID_ID_BAROMETER].PID_Out[THROTTLE];//*throttleRate;
|
int16_t throttle = PidProfile[PID_ID_BAROMETER].PID_Out[THROTTLE];
|
||||||
|
|
||||||
if (PidProfile[PID_ID_BAROMETER].pidEnabled && flags_IsSet_ID(systemFlags_flightmode_barometer_id)) throttle += HoverForce;
|
if (PidProfile[PID_ID_BAROMETER].pidEnabled && flags_IsSet_ID(systemFlags_flightmode_barometer_id)) throttle += HoverForce;
|
||||||
|
|
||||||
|
throttle = (throttle - 1000)/throttleRate + 1000;
|
||||||
|
|
||||||
/* Mixer Full Scale enabled */
|
/* Mixer Full Scale enabled */
|
||||||
if (flags_IsSet_ID(systemFlags_mixerfullscale_id))
|
if (flags_IsSet_ID(systemFlags_mixerfullscale_id))
|
||||||
{
|
{
|
||||||
|
Reference in New Issue
Block a user