Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • opensource/ardupilot
  • opensource/baitboat
2 results
Show changes
Commits on Source (1)
......@@ -77,18 +77,9 @@ static void stabilize_roll(float speed_scaler)
if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;
}
switch (g.att_controller) {
case ATT_CONTROL_APMCONTROL:
// calculate roll and pitch control using new APM_Control library
g.channel_roll.servo_out = g.rollController.get_servo_out(nav_roll_cd, speed_scaler, control_mode == STABILIZE, g.flybywire_airspeed_min);
break;
default:
// Calculate dersired servo output for the roll
// ---------------------------------------------
g.channel_roll.servo_out = g.pidServoRoll.get_pid_4500((nav_roll_cd - ahrs.roll_sensor), speed_scaler);
break;
}
// Calculate dersired servo output for the roll
// ---------------------------------------------
g.channel_roll.servo_out = g.pidServoRoll.get_pid_4500((nav_roll_cd - ahrs.roll_sensor), speed_scaler);
}
/*
......@@ -99,26 +90,13 @@ static void stabilize_roll(float speed_scaler)
static void stabilize_pitch(float speed_scaler)
{
int32_t demanded_pitch = nav_pitch_cd + g.pitch_trim_cd + g.channel_throttle.servo_out * g.kff_throttle_to_pitch;
switch (g.att_controller) {
case ATT_CONTROL_APMCONTROL: {
g.channel_pitch.servo_out = g.pitchController.get_servo_out(demanded_pitch,
speed_scaler,
control_mode == STABILIZE,
g.flybywire_airspeed_min, g.flybywire_airspeed_max);
break;
}
default: {
int32_t tempcalc = demanded_pitch - ahrs.pitch_sensor;
tempcalc += fabsf(ahrs.roll_sensor * g.kff_pitch_compensation);
if (abs(ahrs.roll_sensor) > 9000) {
// when flying upside down the elevator control is inverted
tempcalc = -tempcalc;
}
g.channel_pitch.servo_out = g.pidServoPitch.get_pid_4500(tempcalc, speed_scaler);
break;
}
int32_t tempcalc = demanded_pitch - ahrs.pitch_sensor;
tempcalc += fabsf(ahrs.roll_sensor * g.kff_pitch_compensation);
if (abs(ahrs.roll_sensor) > 9000) {
// when flying upside down the elevator control is inverted
tempcalc = -tempcalc;
}
g.channel_pitch.servo_out = g.pidServoPitch.get_pid_4500(tempcalc, speed_scaler);
}
/*
......@@ -346,20 +324,10 @@ static void calc_nav_yaw(float speed_scaler, float ch4_inf)
return;
}
switch (g.att_controller) {
case ATT_CONTROL_APMCONTROL:
g.channel_rudder.servo_out = g.yawController.get_servo_out(speed_scaler,
control_mode == STABILIZE,
g.flybywire_airspeed_min, g.flybywire_airspeed_max);
break;
default:
// a PID to coordinate the turn (drive y axis accel to zero)
float temp_y = ins.get_accel().y;
int32_t error = -temp_y * 100.0f;
g.channel_rudder.servo_out = g.pidServoRudder.get_pid_4500(error, speed_scaler);
break;
}
// a PID to coordinate the turn (drive y axis accel to zero)
float temp_y = ins.get_accel().y;
int32_t error = -temp_y * 100.0f;
g.channel_rudder.servo_out = g.pidServoRudder.get_pid_4500(error, speed_scaler);
// add in rudder mixing from roll
g.channel_rudder.servo_out += g.channel_roll.servo_out * g.kff_rudder_mix;
......
......@@ -264,9 +264,6 @@ public:
// navigation controller type. See AP_Navigation::ControllerType
AP_Int8 nav_controller;
// attitude controller type.
AP_Int8 att_controller;
// Estimation
//
AP_Float altitude_mix;
......
......@@ -138,13 +138,6 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(nav_controller, "NAV_CONTROLLER", AP_Navigation::CONTROLLER_L1),
// @Param: ATT_CONTROLLER
// @DisplayName: Attitude controller selection
// @Description: Which attitude (roll, pitch, yaw) controller to enable
// @Values: 0:PID,1:APMControl
// @User: Standard
GSCALAR(att_controller, "ATT_CONTROLLER", ATT_CONTROL_PID),
// @Param: ALT_MIX
// @DisplayName: Gps to Baro Mix
// @Description: The percent of mixing between gps altitude and baro altitude. 0 = 100% gps, 1 = 100% baro
......@@ -691,18 +684,6 @@ const AP_Param::Info var_info[] PROGMEM = {
GGROUP(pidServoPitch, "PTCH2SRV_", PID),
GGROUP(pidServoRudder, "YW2SRV_", PID),
// @Group: CTL_RLL_
// @Path: ../libraries/APM_Control/AP_RollController.cpp
GGROUP(rollController, "CTL_RLL_", AP_RollController),
// @Group: CTL_PTCH_
// @Path: ../libraries/APM_Control/AP_PitchController.cpp
GGROUP(pitchController, "CTL_PTCH_", AP_PitchController),
// @Group: CTL_YAW_
// @Path: ../libraries/APM_Control/AP_YawController.cpp
GGROUP(yawController, "CTL_YAW_", AP_YawController),
// variables not in the g class which contain EEPROM saved variables
// @Group: COMPASS_
......