mirror of https://github.com/ArduPilot/ardupilot
roughed in an expo option idea
made min and max values 1100, 1900 removed hard coded init for camera values
This commit is contained in:
parent
1689a9857c
commit
cd72e6bea9
|
@ -4,19 +4,9 @@
|
|||
|
||||
static void init_camera()
|
||||
{
|
||||
// ch 6 high(right) is down.
|
||||
g.rc_camera_pitch.set_angle(4500);
|
||||
g.rc_camera_pitch.radio_min = 1200;
|
||||
g.rc_camera_pitch.radio_trim = 1500;
|
||||
g.rc_camera_pitch.radio_max = 1900;
|
||||
//g.rc_camera_pitch.set_reverse(1);
|
||||
|
||||
// ch 6 high right is down.
|
||||
|
||||
|
||||
g.rc_camera_roll.set_angle(4500);
|
||||
g.rc_camera_roll.radio_min = 1000;
|
||||
g.rc_camera_roll.radio_trim = 1500;
|
||||
g.rc_camera_roll.radio_max = 2000;
|
||||
|
||||
g.rc_camera_roll.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||
g.rc_camera_pitch.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||
|
|
|
@ -98,6 +98,12 @@ RC_Channel::set_pwm(int pwm)
|
|||
//if (fabs(scale_output) > 0){
|
||||
// control_in *= scale_output;
|
||||
//}
|
||||
/*
|
||||
if(expo) {
|
||||
long temp = control_in;
|
||||
temp = (temp * temp) / (long)_high;
|
||||
control_in = (int)((control_in >= 0) ? temp : -temp);
|
||||
}*/
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -22,9 +22,9 @@ class RC_Channel{
|
|||
///
|
||||
RC_Channel(AP_Var::Key key, const prog_char_t *name) :
|
||||
_group(key, name),
|
||||
radio_min (&_group, 0, 1500, name ? PSTR("MIN") : 0), // suppress name if group has no name
|
||||
radio_min (&_group, 0, 1100, name ? PSTR("MIN") : 0), // suppress name if group has no name
|
||||
radio_trim(&_group, 1, 1500, name ? PSTR("TRIM") : 0),
|
||||
radio_max (&_group, 2, 1500, name ? PSTR("MAX") : 0),
|
||||
radio_max (&_group, 2, 1900, name ? PSTR("MAX") : 0),
|
||||
_high(1),
|
||||
_filter(true),
|
||||
_reverse (&_group, 3, 1, name ? PSTR("REV") : 0),
|
||||
|
|
Loading…
Reference in New Issue