mirror of https://github.com/ArduPilot/ardupilot
minor cosmetics
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2846 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
c22ebd22b4
commit
9eb9f12fb0
|
@ -8,19 +8,16 @@ void init_camera()
|
||||||
g.rc_camera_pitch.radio_min = 1000;
|
g.rc_camera_pitch.radio_min = 1000;
|
||||||
g.rc_camera_pitch.radio_trim = 1500;
|
g.rc_camera_pitch.radio_trim = 1500;
|
||||||
g.rc_camera_pitch.radio_max = 2000;
|
g.rc_camera_pitch.radio_max = 2000;
|
||||||
g.rc_camera_pitch.set_reverse(g.cam_pitch_reverse);
|
|
||||||
|
|
||||||
g.rc_camera_roll.set_angle(4500);
|
g.rc_camera_roll.set_angle(4500);
|
||||||
g.rc_camera_roll.radio_min = 1000;
|
g.rc_camera_roll.radio_min = 1000;
|
||||||
g.rc_camera_roll.radio_trim = 1500;
|
g.rc_camera_roll.radio_trim = 1500;
|
||||||
g.rc_camera_roll.radio_max = 2000;
|
g.rc_camera_roll.radio_max = 2000;
|
||||||
g.rc_camera_roll.set_reverse(g.cam_roll_reverse);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
camera_stabilization()
|
camera_stabilization()
|
||||||
{
|
{
|
||||||
|
|
||||||
// PITCH
|
// PITCH
|
||||||
// -----
|
// -----
|
||||||
// allow control mixing
|
// allow control mixing
|
||||||
|
|
|
@ -201,8 +201,8 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
|
||||||
motor_out[2],
|
motor_out[2],
|
||||||
motor_out[3],
|
motor_out[3],
|
||||||
motor_out[4],
|
motor_out[4],
|
||||||
|
motor_out[6],
|
||||||
motor_out[7],
|
motor_out[7],
|
||||||
motor_out[8],
|
|
||||||
0);
|
0);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
|
@ -104,8 +104,6 @@ public:
|
||||||
k_param_throttle_cruise,
|
k_param_throttle_cruise,
|
||||||
k_param_flight_modes,
|
k_param_flight_modes,
|
||||||
k_param_esc_calibrate,
|
k_param_esc_calibrate,
|
||||||
k_param_cam_pitch_reverse,
|
|
||||||
k_param_cam_roll_reverse,
|
|
||||||
|
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
@ -242,9 +240,6 @@ public:
|
||||||
RC_Channel rc_camera_pitch;
|
RC_Channel rc_camera_pitch;
|
||||||
RC_Channel rc_camera_roll;
|
RC_Channel rc_camera_roll;
|
||||||
|
|
||||||
AP_Int8 cam_pitch_reverse;
|
|
||||||
AP_Int8 cam_roll_reverse;
|
|
||||||
|
|
||||||
// PID controllers
|
// PID controllers
|
||||||
PID pid_rate_roll;
|
PID pid_rate_roll;
|
||||||
PID pid_rate_pitch;
|
PID pid_rate_pitch;
|
||||||
|
@ -330,12 +325,8 @@ public:
|
||||||
rc_6 (k_param_rc_6, PSTR("RC6_")),
|
rc_6 (k_param_rc_6, PSTR("RC6_")),
|
||||||
rc_7 (k_param_rc_7, PSTR("RC7_")),
|
rc_7 (k_param_rc_7, PSTR("RC7_")),
|
||||||
rc_8 (k_param_rc_8, PSTR("RC8_")),
|
rc_8 (k_param_rc_8, PSTR("RC8_")),
|
||||||
rc_camera_pitch (k_param_rc_9, NULL),
|
rc_camera_pitch (k_param_rc_9, PSTR("RC_CP_")),
|
||||||
rc_camera_roll (k_param_rc_10, NULL),
|
rc_camera_roll (k_param_rc_10, PSTR("RC_CR_")),
|
||||||
|
|
||||||
cam_pitch_reverse (0, k_param_cam_pitch_reverse, PSTR("CAM_P_REV")),
|
|
||||||
cam_roll_reverse (0, k_param_cam_roll_reverse, PSTR("CAM_R_REV")),
|
|
||||||
|
|
||||||
|
|
||||||
// PID controller group key name initial P initial I initial D initial imax
|
// PID controller group key name initial P initial I initial D initial imax
|
||||||
//--------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
//--------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||||
|
|
|
@ -14,6 +14,7 @@ static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_wp_nav(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_wp_nav(uint8_t argc, const Menu::arg *argv);
|
||||||
|
//static int8_t test_reverse(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_tuning(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_tuning(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_current(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_current(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
|
||||||
|
@ -72,6 +73,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||||
{"eedump", test_eedump},
|
{"eedump", test_eedump},
|
||||||
{"rawgps", test_rawgps},
|
{"rawgps", test_rawgps},
|
||||||
{"mission", test_mission},
|
{"mission", test_mission},
|
||||||
|
//{"reverse", test_reverse},
|
||||||
//{"wp", test_wp_nav},
|
//{"wp", test_wp_nav},
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -81,7 +83,7 @@ MENU(test_menu, "test", test_menu_commands);
|
||||||
int8_t
|
int8_t
|
||||||
test_mode(uint8_t argc, const Menu::arg *argv)
|
test_mode(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
Serial.printf_P(PSTR("Test Mode\n\n"));
|
//Serial.printf_P(PSTR("Test Mode\n\n"));
|
||||||
test_menu.run();
|
test_menu.run();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -899,6 +901,45 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/*
|
||||||
|
static int8_t
|
||||||
|
test_reverse(uint8_t argc, const Menu::arg *argv)
|
||||||
|
{
|
||||||
|
print_hit_enter();
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
while(1){
|
||||||
|
delay(20);
|
||||||
|
|
||||||
|
// Filters radio input - adjust filters in the radio.pde file
|
||||||
|
// ----------------------------------------------------------
|
||||||
|
g.rc_4.set_reverse(0);
|
||||||
|
g.rc_4.set_pwm(APM_RC.InputCh(CH_4));
|
||||||
|
g.rc_4.servo_out = g.rc_4.control_in;
|
||||||
|
g.rc_4.calc_pwm();
|
||||||
|
Serial.printf_P(PSTR("PWM:%d input: %d\toutput%d "),
|
||||||
|
APM_RC.InputCh(CH_4),
|
||||||
|
g.rc_4.control_in,
|
||||||
|
g.rc_4.radio_out);
|
||||||
|
APM_RC.OutputCh(CH_6, g.rc_4.radio_out);
|
||||||
|
|
||||||
|
|
||||||
|
g.rc_4.set_reverse(1);
|
||||||
|
g.rc_4.set_pwm(APM_RC.InputCh(CH_4));
|
||||||
|
g.rc_4.servo_out = g.rc_4.control_in;
|
||||||
|
g.rc_4.calc_pwm();
|
||||||
|
Serial.printf_P(PSTR("\trev input: %d\toutput%d\n"),
|
||||||
|
g.rc_4.control_in,
|
||||||
|
g.rc_4.radio_out);
|
||||||
|
|
||||||
|
APM_RC.OutputCh(CH_7, g.rc_4.radio_out);
|
||||||
|
|
||||||
|
if(Serial.available() > 0){
|
||||||
|
g.rc_4.set_reverse(0);
|
||||||
|
return (0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
test the sonar
|
test the sonar
|
||||||
|
|
Loading…
Reference in New Issue