From 9eda7f1b5ba626d56672c574827e34c4750f5b73 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Tue, 7 Feb 2017 22:51:37 -0500 Subject: [PATCH] Sub: Add forward and strafe input channels --- ArduSub/Copter.h | 2 ++ ArduSub/radio.cpp | 6 ++++++ 2 files changed, 8 insertions(+) diff --git a/ArduSub/Copter.h b/ArduSub/Copter.h index eb15a6aa53..32460b1e62 100644 --- a/ArduSub/Copter.h +++ b/ArduSub/Copter.h @@ -162,6 +162,8 @@ private: RC_Channel *channel_pitch; RC_Channel *channel_throttle; RC_Channel *channel_yaw; + RC_Channel *channel_forward; + RC_Channel *channel_strafe; // Dataflash DataFlash_Class DataFlash{FIRMWARE_STRING}; diff --git a/ArduSub/radio.cpp b/ArduSub/radio.cpp index faa517765c..9cffddad9d 100644 --- a/ArduSub/radio.cpp +++ b/ArduSub/radio.cpp @@ -27,16 +27,22 @@ void Copter::init_rc_in() channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1); channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1); channel_yaw = RC_Channel::rc_channel(rcmap.yaw()-1); + channel_forward = RC_Channel::rc_channel(rcmap.forward()-1); + channel_strafe = RC_Channel::rc_channel(rcmap.strafe()-1); // set rc channel ranges channel_roll->set_angle(ROLL_PITCH_INPUT_MAX); channel_pitch->set_angle(ROLL_PITCH_INPUT_MAX); channel_yaw->set_angle(4500); channel_throttle->set_range(g.throttle_min, THR_MAX); + channel_forward->set_angle(4500); + channel_strafe->set_angle(4500); channel_roll->set_type(RC_CHANNEL_TYPE_ANGLE_RAW); channel_pitch->set_type(RC_CHANNEL_TYPE_ANGLE_RAW); channel_yaw->set_type(RC_CHANNEL_TYPE_ANGLE_RAW); + channel_forward->set_type(RC_CHANNEL_TYPE_ANGLE_RAW); + channel_strafe->set_type(RC_CHANNEL_TYPE_ANGLE_RAW); //set auxiliary servo ranges g.rc_5.set_range(0,1000);