Browse Source

Copter: added HELI_QUAD

mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
18f04abfe8
  1. 12
      ArduCopter/system.cpp

12
ArduCopter/system.cpp

@ -439,7 +439,8 @@ bool Copter::should_log(uint32_t mask)
void Copter::set_default_frame_class() void Copter::set_default_frame_class()
{ {
if (FRAME_CONFIG == HELI_FRAME && if (FRAME_CONFIG == HELI_FRAME &&
g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_DUAL) { g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_DUAL &&
g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD) {
g2.frame_class.set(AP_Motors::MOTOR_FRAME_HELI); g2.frame_class.set(AP_Motors::MOTOR_FRAME_HELI);
} }
} }
@ -459,6 +460,7 @@ uint8_t Copter::get_frame_mav_type()
return MAV_TYPE_OCTOROTOR; return MAV_TYPE_OCTOROTOR;
case AP_Motors::MOTOR_FRAME_HELI: case AP_Motors::MOTOR_FRAME_HELI:
case AP_Motors::MOTOR_FRAME_HELI_DUAL: case AP_Motors::MOTOR_FRAME_HELI_DUAL:
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
return MAV_TYPE_HELICOPTER; return MAV_TYPE_HELICOPTER;
case AP_Motors::MOTOR_FRAME_TRI: case AP_Motors::MOTOR_FRAME_TRI:
return MAV_TYPE_TRICOPTER; return MAV_TYPE_TRICOPTER;
@ -491,6 +493,8 @@ const char* Copter::get_frame_string()
return "HELI"; return "HELI";
case AP_Motors::MOTOR_FRAME_HELI_DUAL: case AP_Motors::MOTOR_FRAME_HELI_DUAL:
return "HELI_DUAL"; return "HELI_DUAL";
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
return "HELI_QUAD";
case AP_Motors::MOTOR_FRAME_TRI: case AP_Motors::MOTOR_FRAME_TRI:
return "TRI"; return "TRI";
case AP_Motors::MOTOR_FRAME_SINGLE: case AP_Motors::MOTOR_FRAME_SINGLE:
@ -547,6 +551,12 @@ void Copter::allocate_motors(void)
motors_var_info = AP_MotorsHeli_Dual::var_info; motors_var_info = AP_MotorsHeli_Dual::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI); AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
break; break;
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
motors = new AP_MotorsHeli_Quad(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsHeli_Quad::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
break;
case AP_Motors::MOTOR_FRAME_HELI: case AP_Motors::MOTOR_FRAME_HELI:
default: default:

Loading…
Cancel
Save