Skip to content

Commit

Permalink
Copter: combined tri, single, coax and multicopter into a single build
Browse files Browse the repository at this point in the history
this allows copter to be just 2 builds, one for heli, and one for
everything else
  • Loading branch information
tridge committed Jan 12, 2017
1 parent 5cf1c08 commit 0f6d0c5
Show file tree
Hide file tree
Showing 50 changed files with 1,087 additions and 1,062 deletions.
28 changes: 14 additions & 14 deletions ArduCopter/ArduCopter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ void Copter::fast_loop()
read_AHRS();

// run low level rate controllers that only require IMU data
attitude_control.rate_controller_run();
attitude_control->rate_controller_run();

#if FRAME_CONFIG == HELI_FRAME
update_heli_control_dynamics();
Expand Down Expand Up @@ -362,7 +362,7 @@ void Copter::update_batt_compass(void)

if(g.compass_enabled) {
// update compass with throttle value - used for compassmot
compass.set_throttle(motors.get_throttle());
compass.set_throttle(motors->get_throttle());
compass.read();
// log compass information
if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) {
Expand All @@ -378,11 +378,11 @@ void Copter::ten_hz_logging_loop()
// log attitude data if we're not already logging at the higher rate
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
Log_Write_Attitude();
DataFlash.Log_Write_Rate(ahrs, motors, attitude_control, pos_control);
DataFlash.Log_Write_Rate(ahrs, *motors, *attitude_control, *pos_control);
if (should_log(MASK_LOG_PID)) {
DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
}
}
Expand All @@ -405,7 +405,7 @@ void Copter::ten_hz_logging_loop()
DataFlash.Log_Write_Vibration(ins);
}
if (should_log(MASK_LOG_CTUN)) {
attitude_control.control_monitor_log();
attitude_control->control_monitor_log();
Log_Write_Proximity();
Log_Write_Beacon();
}
Expand All @@ -425,11 +425,11 @@ void Copter::twentyfive_hz_logging()
#if HIL_MODE == HIL_MODE_DISABLED
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
Log_Write_Attitude();
DataFlash.Log_Write_Rate(ahrs, motors, attitude_control, pos_control);
DataFlash.Log_Write_Rate(ahrs, *motors, *attitude_control, *pos_control);
if (should_log(MASK_LOG_PID)) {
DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
}
}
Expand Down Expand Up @@ -484,18 +484,18 @@ void Copter::one_hz_loop()

update_arming_checks();

if (!motors.armed()) {
if (!motors->armed()) {
// make it possible to change ahrs orientation at runtime during initial config
ahrs.set_orientation();

update_using_interlock();

// check the user hasn't updated the frame class or type
motors.set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
motors->set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());

#if FRAME_CONFIG != HELI_FRAME
// set all throttle channel settings
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
#endif
}

Expand Down
24 changes: 12 additions & 12 deletions ArduCopter/Attitude.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "Copter.h"

// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw
// result is a number from 2 to 12 with 2 being very sluggish and 12 being very crisp
float Copter::get_smoothing_gain()
{
Expand Down Expand Up @@ -107,7 +107,7 @@ void Copter::update_throttle_hover()
{
#if FRAME_CONFIG != HELI_FRAME
// if not armed or landed exit
if (!motors.armed() || ap.land_complete) {
if (!motors->armed() || ap.land_complete) {
return;
}

Expand All @@ -117,17 +117,17 @@ void Copter::update_throttle_hover()
}

// do not update while climbing or descending
if (!is_zero(pos_control.get_desired_velocity().z)) {
if (!is_zero(pos_control->get_desired_velocity().z)) {
return;
}

// get throttle output
float throttle = motors.get_throttle();
float throttle = motors->get_throttle();

// calc average throttle if we are in a level hover
if (throttle > 0.0f && abs(climb_rate) < 60 && labs(ahrs.roll_sensor) < 500 && labs(ahrs.pitch_sensor) < 500) {
// Can we set the time constant automatically
motors.update_throttle_hover(0.01f);
motors->update_throttle_hover(0.01f);
}
#endif
}
Expand All @@ -136,7 +136,7 @@ void Copter::update_throttle_hover()
void Copter::set_throttle_takeoff()
{
// tell position controller to reset alt target and reset I terms
pos_control.init_takeoff();
pos_control->init_takeoff();
}

// transform pilot's manual throttle input to make hover throttle mid stick
Expand All @@ -146,7 +146,7 @@ void Copter::set_throttle_takeoff()
float Copter::get_pilot_desired_throttle(int16_t throttle_control, float thr_mid)
{
if (thr_mid <= 0.0f) {
thr_mid = motors.get_throttle_hover();
thr_mid = motors->get_throttle_hover();
}

int16_t mid_stick = channel_throttle->get_control_mid();
Expand Down Expand Up @@ -218,7 +218,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
float Copter::get_non_takeoff_throttle()
{
return MAX(0,motors.get_throttle_hover()/2.0f);
return MAX(0,motors->get_throttle_hover()/2.0f);
}

// get_surface_tracking_climb_rate - hold copter at the desired distance above the ground
Expand All @@ -240,7 +240,7 @@ float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current
last_call_ms = now;

// adjust rangefinder target alt if motors have not hit their limits
if ((target_rate<0 && !motors.limit.throttle_lower) || (target_rate>0 && !motors.limit.throttle_upper)) {
if ((target_rate<0 && !motors->limit.throttle_lower) || (target_rate>0 && !motors->limit.throttle_upper)) {
target_rangefinder_alt += target_rate * dt;
}

Expand Down Expand Up @@ -286,9 +286,9 @@ float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current
void Copter::set_accel_throttle_I_from_pilot_throttle()
{
// get last throttle input sent to attitude controller
float pilot_throttle = constrain_float(attitude_control.get_throttle_in(), 0.0f, 1.0f);
float pilot_throttle = constrain_float(attitude_control->get_throttle_in(), 0.0f, 1.0f);
// shift difference between pilot's throttle and hover throttle into accelerometer I
g.pid_accel_z.set_integrator((pilot_throttle-motors.get_throttle_hover()) * 1000.0f);
g.pid_accel_z.set_integrator((pilot_throttle-motors->get_throttle_hover()) * 1000.0f);
}

// updates position controller's maximum altitude using fence and EKF limits
Expand All @@ -312,7 +312,7 @@ void Copter::update_poscon_alt_max()
}

// pass limit to pos controller
pos_control.set_alt_max(alt_limit_cm);
pos_control->set_alt_max(alt_limit_cm);
}

// rotate vector from vehicle's perspective to North-East frame
Expand Down
7 changes: 0 additions & 7 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ Copter::Copter(void) :
FUNCTOR_BIND_MEMBER(&Copter::verify_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void)),
control_mode(STABILIZE),
motors(MAIN_LOOP_RATE),
scaleLongDown(1),
wp_bearing(0),
home_bearing(0),
Expand Down Expand Up @@ -66,12 +65,6 @@ Copter::Copter(void) :
condition_start(0),
G_Dt(MAIN_LOOP_SECONDS),
inertial_nav(ahrs),
attitude_control(ahrs, aparm, motors, MAIN_LOOP_SECONDS),
pos_control(ahrs, inertial_nav, motors, attitude_control,
g.p_alt_hold, g.p_vel_z, g.pid_accel_z,
g.p_pos_xy, g.pi_vel_xy),
wp_nav(inertial_nav, ahrs, pos_control, attitude_control),
circle_nav(inertial_nav, ahrs, pos_control),
pmTest1(0),
fast_loopTimer(0),
mainLoop_count(0),
Expand Down
27 changes: 8 additions & 19 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -326,21 +326,13 @@ class Copter : public AP_HAL::HAL::Callbacks {
} sensor_health;

// Motor Output
#if FRAME_CONFIG == QUAD_FRAME || FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME || FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
#define MOTOR_CLASS AP_MotorsMatrix
#elif FRAME_CONFIG == TRI_FRAME
#define MOTOR_CLASS AP_MotorsTri
#elif FRAME_CONFIG == HELI_FRAME
#if FRAME_CONFIG == HELI_FRAME
#define MOTOR_CLASS AP_MotorsHeli_Single
#elif FRAME_CONFIG == SINGLE_FRAME
#define MOTOR_CLASS AP_MotorsSingle
#elif FRAME_CONFIG == COAX_FRAME
#define MOTOR_CLASS AP_MotorsCoax
#else
#error Unrecognised frame type
#define MOTOR_CLASS AP_MotorsMulticopter
#endif

MOTOR_CLASS motors;
MOTOR_CLASS *motors;

// GPS variables
// Sometimes we need to remove the scaling for distance calcs
Expand Down Expand Up @@ -491,14 +483,10 @@ class Copter : public AP_HAL::HAL::Callbacks {

// Attitude, Position and Waypoint navigation objects
// To-Do: move inertial nav up or other navigation variables down here
#if FRAME_CONFIG == HELI_FRAME
AC_AttitudeControl_Heli attitude_control;
#else
AC_AttitudeControl_Multi attitude_control;
#endif
AC_PosControl pos_control;
AC_WPNav wp_nav;
AC_Circle circle_nav;
AC_AttitudeControl *attitude_control;
AC_PosControl *pos_control;
AC_WPNav *wp_nav;
AC_Circle *circle_nav;

// Performance monitoring
int16_t pmTest1;
Expand Down Expand Up @@ -1085,6 +1073,7 @@ class Copter : public AP_HAL::HAL::Callbacks {
void check_usb_mux(void);
bool should_log(uint32_t mask);
void set_default_frame_class();
void allocate_motors(void);
uint8_t get_frame_mav_type();
const char* get_frame_string();
bool current_mode_has_user_takeoff(bool must_navigate);
Expand Down
Loading

0 comments on commit 0f6d0c5

Please sign in to comment.