From 213eaa8db6e66d8b4f8d70058cd722753c99a1f9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 25 Mar 2013 11:48:06 +0900 Subject: [PATCH] Copter: integrate draft RCMapper --- ArduCopter/ArduCopter.pde | 2 ++ ArduCopter/Parameters.h | 1 + ArduCopter/Parameters.pde | 4 ++++ ArduCopter/radio.pde | 8 ++++---- 4 files changed, 11 insertions(+), 4 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 2002bb5889..c10fe77279 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -103,6 +103,7 @@ #include // memory limit checker #include // software in the loop support #include // main loop scheduler +#include // RC input mapping library // AP_HAL to Arduino compatibility layer #include "compat.h" @@ -405,6 +406,7 @@ static int8_t control_mode = STABILIZE; // Used to maintain the state of the previous control switch position // This is set to -1 when we need to re-read the switch static uint8_t oldSwitchPosition; +static RCMapper rcmap; // receiver RSSI static uint8_t receiver_rssi; diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 4919cb7a71..19326b4c2b 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -200,6 +200,7 @@ public: k_param_rc_9, k_param_rc_12, k_param_failsafe_gcs, // 198 + k_param_rcmap, // // 200: flight modes diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 2caf7be358..7f09d7e4ec 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -999,6 +999,10 @@ const AP_Param::Info var_info[] PROGMEM = { GOBJECT(motors, "MOT_", AP_Motors), #endif + // @Group: RCMAP_ + // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp + GOBJECT(rcmap, "RCMAP_", RCMapper), + AP_VAREND }; diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 78cf3c94fc..d3435f65cd 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -133,12 +133,12 @@ static void read_radio() ap_system.new_radio_frame = true; uint16_t periods[8]; hal.rcin->read(periods,8); - g.rc_1.set_pwm(periods[0]); - g.rc_2.set_pwm(periods[1]); + g.rc_1.set_pwm(periods[rcmap.roll()]); + g.rc_2.set_pwm(periods[rcmap.pitch()]); - set_throttle_and_failsafe(periods[2]); + set_throttle_and_failsafe(periods[rcmap.throttle()]); - g.rc_4.set_pwm(periods[3]); + g.rc_4.set_pwm(periods[rcmap.yaw()]); g.rc_5.set_pwm(periods[4]); g.rc_6.set_pwm(periods[5]); g.rc_7.set_pwm(periods[6]);