mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: use RC_Channel::rc_channel() instead of rc_ch[]
This commit is contained in:
parent
0438952a8b
commit
9076f6a1d0
|
@ -216,8 +216,6 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
extern RC_Channel* rc_ch[8];
|
|
||||||
|
|
||||||
AP_Mount::AP_Mount(const struct Location *current_loc, GPS *&gps, AP_AHRS *ahrs, uint8_t id) :
|
AP_Mount::AP_Mount(const struct Location *current_loc, GPS *&gps, AP_AHRS *ahrs, uint8_t id) :
|
||||||
_gps(gps)
|
_gps(gps)
|
||||||
{
|
{
|
||||||
|
@ -342,34 +340,35 @@ void AP_Mount::update_mount_position()
|
||||||
case MAV_MOUNT_MODE_RC_TARGETING:
|
case MAV_MOUNT_MODE_RC_TARGETING:
|
||||||
{
|
{
|
||||||
#if MNT_JSTICK_SPD_OPTION == ENABLED
|
#if MNT_JSTICK_SPD_OPTION == ENABLED
|
||||||
|
#define rc_ch(i) RC_Channel::rc_channel(i)
|
||||||
if (_joystick_speed) { // for spring loaded joysticks
|
if (_joystick_speed) { // for spring loaded joysticks
|
||||||
// allow pilot speed position input to come directly from an RC_Channel
|
// allow pilot speed position input to come directly from an RC_Channel
|
||||||
if (_roll_rc_in && (rc_ch[_roll_rc_in-1])) {
|
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;
|
_roll_control_angle += rc_ch(_roll_rc_in-1)->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_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 (_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])) {
|
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;
|
_tilt_control_angle += rc_ch(_tilt_rc_in-1)->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_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 (_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])) {
|
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;
|
_pan_control_angle += rc_ch(_pan_rc_in-1)->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_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);
|
if (_pan_control_angle > radians(_pan_angle_max*0.01f)) _pan_control_angle = radians(_pan_angle_max*0.01f);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
#endif
|
#endif
|
||||||
// allow pilot position input to come directly from an RC_Channel
|
// allow pilot position input to come directly from an RC_Channel
|
||||||
if (_roll_rc_in && (rc_ch[_roll_rc_in-1])) {
|
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);
|
_roll_control_angle = angle_input_rad(rc_ch(_roll_rc_in-1), _roll_angle_min, _roll_angle_max);
|
||||||
}
|
}
|
||||||
if (_tilt_rc_in && (rc_ch[_tilt_rc_in-1])) {
|
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);
|
_tilt_control_angle = angle_input_rad(rc_ch(_tilt_rc_in-1), _tilt_angle_min, _tilt_angle_max);
|
||||||
}
|
}
|
||||||
if (_pan_rc_in && (rc_ch[_pan_rc_in-1])) {
|
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);
|
_pan_control_angle = angle_input_rad(rc_ch(_pan_rc_in-1), _pan_angle_min, _pan_angle_max);
|
||||||
}
|
}
|
||||||
#if MNT_JSTICK_SPD_OPTION == ENABLED
|
#if MNT_JSTICK_SPD_OPTION == ENABLED
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue