mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Rover: added LEARN_CH parameter
this allows the learning channel to be set, for transmitters where setting up channel 7 is difficult
This commit is contained in:
parent
d0c69b36b6
commit
135146c735
@ -126,6 +126,7 @@ static RCMapper rcmap;
|
||||
// primary control channels
|
||||
static RC_Channel *channel_steer;
|
||||
static RC_Channel *channel_throttle;
|
||||
static RC_Channel *channel_learn;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// prototypes
|
||||
@ -422,7 +423,6 @@ static bool ch7_flag;
|
||||
// This register tracks the current Mission Command index when writing
|
||||
// a mission using CH7 in flight
|
||||
static int8_t CH7_wp_index;
|
||||
float tuning_value;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Battery Sensors
|
||||
|
@ -122,6 +122,7 @@ public:
|
||||
k_param_mode4,
|
||||
k_param_mode5,
|
||||
k_param_mode6,
|
||||
k_param_learn_channel,
|
||||
|
||||
//
|
||||
// 220: Waypoint data
|
||||
@ -231,6 +232,7 @@ public:
|
||||
AP_Int8 mode4;
|
||||
AP_Int8 mode5;
|
||||
AP_Int8 mode6;
|
||||
AP_Int8 learn_channel;
|
||||
|
||||
// Waypoints
|
||||
//
|
||||
|
@ -348,6 +348,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_debounce, "SONAR_DEBOUNCE", 2),
|
||||
|
||||
// @Param: LEARN_CH
|
||||
// @DisplayName: Learning channel
|
||||
// @Description: RC Channel to use for learning waypoints
|
||||
// @User: Advanced
|
||||
GSCALAR(learn_channel, "LEARN_CH", 7),
|
||||
|
||||
// @Param: MODE_CH
|
||||
// @DisplayName: Mode channel
|
||||
// @Description: RC Channel to use for driving mode control
|
||||
|
@ -59,7 +59,7 @@ static void read_trim_switch()
|
||||
case CH7_DO_NOTHING:
|
||||
break;
|
||||
case CH7_SAVE_WP:
|
||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER) {
|
||||
if (channel_learn->radio_in > CH_7_PWM_TRIGGER) {
|
||||
// switch is engaged
|
||||
ch7_flag = true;
|
||||
} else { // switch is disengaged
|
||||
|
@ -7,6 +7,7 @@ static void set_control_channels(void)
|
||||
{
|
||||
channel_steer = RC_Channel::rc_channel(rcmap.roll()-1);
|
||||
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
||||
channel_learn = RC_Channel::rc_channel(g.learn_channel-1);
|
||||
|
||||
// set rc channel ranges
|
||||
channel_steer->set_angle(SERVO_MAX);
|
||||
|
@ -140,9 +140,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
// ------------------------------
|
||||
set_servos();
|
||||
|
||||
tuning_value = constrain_float(((float)(g.rc_7.radio_in - g.rc_7.radio_min) / (float)(g.rc_7.radio_max - g.rc_7.radio_min)),0,1);
|
||||
|
||||
cliSerial->printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d Tuning = %2.3f\n"),
|
||||
cliSerial->printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
channel_steer->control_in,
|
||||
g.rc_2.control_in,
|
||||
channel_throttle->control_in,
|
||||
@ -150,8 +148,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
g.rc_5.control_in,
|
||||
g.rc_6.control_in,
|
||||
g.rc_7.control_in,
|
||||
g.rc_8.control_in,
|
||||
tuning_value);
|
||||
g.rc_8.control_in);
|
||||
|
||||
if(cliSerial->available() > 0){
|
||||
return (0);
|
||||
|
Loading…
Reference in New Issue
Block a user