ArduCopter: Add implementation of motors_output_enable to each motors_ frame type

This commit is contained in:
Pat Hickey 2012-01-17 11:47:27 -08:00
parent a13e371d1e
commit 2bd2e9c774
6 changed files with 59 additions and 0 deletions

View File

@ -10,6 +10,16 @@ static void init_motors_out()
#endif
}
static void motors_output_enable()
{
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_3);
APM_RC.enable_out(MOT_4);
APM_RC.enable_out(MOT_5);
APM_RC.enable_out(MOT_6);
}
static void output_motors_armed()
{
int roll_out, pitch_out;

View File

@ -10,6 +10,18 @@ static void init_motors_out()
#endif
}
static void motors_output_enable()
{
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_3);
APM_RC.enable_out(MOT_4);
APM_RC.enable_out(MOT_5);
APM_RC.enable_out(MOT_6);
APM_RC.enable_out(MOT_7);
APM_RC.enable_out(MOT_8);
}
static void output_motors_armed()
{
int roll_out, pitch_out;

View File

@ -10,6 +10,18 @@ static void init_motors_out()
#endif
}
static void motors_output_enable()
{
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_3);
APM_RC.enable_out(MOT_4);
APM_RC.enable_out(MOT_5);
APM_RC.enable_out(MOT_6);
APM_RC.enable_out(MOT_7);
APM_RC.enable_out(MOT_8);
}
static void output_motors_armed()
{
int roll_out, pitch_out;

View File

@ -9,6 +9,14 @@ static void init_motors_out()
#endif
}
static void motors_output_enable()
{
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_3);
APM_RC.enable_out(MOT_4);
}
static void output_motors_armed()
{
int roll_out, pitch_out;

View File

@ -8,6 +8,13 @@ static void init_motors_out()
#endif
}
static void motors_output_enable()
{
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_4);
}
static void output_motors_armed()
{

View File

@ -12,6 +12,16 @@ static void init_motors_out()
#endif
}
static void motors_output_enable()
{
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_3);
APM_RC.enable_out(MOT_4);
APM_RC.enable_out(MOT_5);
APM_RC.enable_out(MOT_6);
}
static void output_motors_armed()
{
int out_min = g.rc_3.radio_min;