AP_Mount: make the code a bit easier to read

This commit is contained in:
Andrew Tridgell 2013-06-03 16:10:33 +10:00
parent fb9bf21522
commit 033828aeb6

View File

@ -339,36 +339,36 @@ void AP_Mount::update_mount_position()
// RC radio manual angle control, but with stabilization from the AHRS
case MAV_MOUNT_MODE_RC_TARGETING:
{
#define rc_ch(i) RC_Channel::rc_channel(i-1)
#if MNT_JSTICK_SPD_OPTION == ENABLED
#define rc_ch(i) RC_Channel::rc_channel(i)
if (_joystick_speed) { // for spring loaded joysticks
// allow pilot speed position input to come directly from an RC_Channel
if (_roll_rc_in && rc_ch(_roll_rc_in-1)) {
_roll_control_angle += rc_ch(_roll_rc_in-1)->norm_input() * 0.0001f * _joystick_speed;
if (_roll_rc_in && rc_ch(_roll_rc_in)) {
_roll_control_angle += rc_ch(_roll_rc_in)->norm_input() * 0.0001f * _joystick_speed;
if (_roll_control_angle < radians(_roll_angle_min*0.01f)) _roll_control_angle = radians(_roll_angle_min*0.01f);
if (_roll_control_angle > radians(_roll_angle_max*0.01f)) _roll_control_angle = radians(_roll_angle_max*0.01f);
}
if (_tilt_rc_in && (rc_ch(_tilt_rc_in-1))) {
_tilt_control_angle += rc_ch(_tilt_rc_in-1)->norm_input() * 0.0001f * _joystick_speed;
if (_tilt_rc_in && (rc_ch(_tilt_rc_in))) {
_tilt_control_angle += rc_ch(_tilt_rc_in)->norm_input() * 0.0001f * _joystick_speed;
if (_tilt_control_angle < radians(_tilt_angle_min*0.01f)) _tilt_control_angle = radians(_tilt_angle_min*0.01f);
if (_tilt_control_angle > radians(_tilt_angle_max*0.01f)) _tilt_control_angle = radians(_tilt_angle_max*0.01f);
}
if (_pan_rc_in && (rc_ch(_pan_rc_in-1))) {
_pan_control_angle += rc_ch(_pan_rc_in-1)->norm_input() * 0.0001f * _joystick_speed;
if (_pan_rc_in && (rc_ch(_pan_rc_in))) {
_pan_control_angle += rc_ch(_pan_rc_in)->norm_input() * 0.0001f * _joystick_speed;
if (_pan_control_angle < radians(_pan_angle_min*0.01f)) _pan_control_angle = radians(_pan_angle_min*0.01f);
if (_pan_control_angle > radians(_pan_angle_max*0.01f)) _pan_control_angle = radians(_pan_angle_max*0.01f);
}
} else {
#endif
// allow pilot position input to come directly from an RC_Channel
if (_roll_rc_in && (rc_ch(_roll_rc_in-1))) {
_roll_control_angle = angle_input_rad(rc_ch(_roll_rc_in-1), _roll_angle_min, _roll_angle_max);
if (_roll_rc_in && (rc_ch(_roll_rc_in))) {
_roll_control_angle = angle_input_rad(rc_ch(_roll_rc_in), _roll_angle_min, _roll_angle_max);
}
if (_tilt_rc_in && (rc_ch(_tilt_rc_in-1))) {
_tilt_control_angle = angle_input_rad(rc_ch(_tilt_rc_in-1), _tilt_angle_min, _tilt_angle_max);
if (_tilt_rc_in && (rc_ch(_tilt_rc_in))) {
_tilt_control_angle = angle_input_rad(rc_ch(_tilt_rc_in), _tilt_angle_min, _tilt_angle_max);
}
if (_pan_rc_in && (rc_ch(_pan_rc_in-1))) {
_pan_control_angle = angle_input_rad(rc_ch(_pan_rc_in-1), _pan_angle_min, _pan_angle_max);
if (_pan_rc_in && (rc_ch(_pan_rc_in))) {
_pan_control_angle = angle_input_rad(rc_ch(_pan_rc_in), _pan_angle_min, _pan_angle_max);
}
#if MNT_JSTICK_SPD_OPTION == ENABLED
}