From 71716f15ef9256d4f3827ed3d963bd401ff1d69f Mon Sep 17 00:00:00 2001 From: jaxxzer Date: Fri, 8 Jan 2016 18:25:59 -0500 Subject: [PATCH] Update forward and strafe rc channels in the control mode files. --- ArduSub/ArduSub.cpp | 6 ++++-- ArduSub/control_acro.cpp | 5 +++++ ArduSub/control_althold.cpp | 5 +++++ ArduSub/control_stabilize.cpp | 5 +++++ modules/PX4Firmware | 1 - modules/PX4NuttX | 1 - modules/gbenchmark | 1 - modules/uavcan | 1 - modules/waf | 1 - 9 files changed, 19 insertions(+), 7 deletions(-) delete mode 160000 modules/PX4Firmware delete mode 160000 modules/PX4NuttX delete mode 160000 modules/gbenchmark delete mode 160000 modules/uavcan delete mode 160000 modules/waf diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index f02d8e084a..143188c253 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -261,8 +261,10 @@ void Copter::fast_loop() // run low level rate controllers that only require IMU data attitude_control.rate_controller_run(); - motors.set_forward(channel_forward->control_in); - motors.set_strafe(channel_strafe->control_in); + +// moved this to update in control_acro.cpp, control_stabilize.cpp ... +// motors.set_forward(channel_forward->control_in); +// motors.set_strafe(channel_strafe->control_in); #if FRAME_CONFIG == HELI_FRAME update_heli_control_dynamics(); diff --git a/ArduSub/control_acro.cpp b/ArduSub/control_acro.cpp index 4f9cf85ae8..583c668b8f 100644 --- a/ArduSub/control_acro.cpp +++ b/ArduSub/control_acro.cpp @@ -47,6 +47,11 @@ void Copter::acro_run() // output pilot's throttle without angle boost attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); + + //control_in is range 0-1000 + //radio_in is raw pwm value + motors.set_forward(channel_forward->radio_in); + motors.set_strafe(channel_strafe->radio_in); } diff --git a/ArduSub/control_althold.cpp b/ArduSub/control_althold.cpp index ec652e214f..b38f2cad4b 100644 --- a/ArduSub/control_althold.cpp +++ b/ArduSub/control_althold.cpp @@ -158,4 +158,9 @@ void Copter::althold_run() pos_control.update_z_controller(); break; } + + //control_in is range 0-1000 + //radio_in is raw pwm value + motors.set_forward(channel_forward->radio_in); + motors.set_strafe(channel_strafe->radio_in); } diff --git a/ArduSub/control_stabilize.cpp b/ArduSub/control_stabilize.cpp index 9ad9fce66f..fc0c5e2001 100644 --- a/ArduSub/control_stabilize.cpp +++ b/ArduSub/control_stabilize.cpp @@ -57,4 +57,9 @@ void Copter::stabilize_run() // output pilot's throttle attitude_control.set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt); + + //control_in is range 0-1000 + //radio_in is raw pwm value + motors.set_forward(channel_forward->radio_in); + motors.set_strafe(channel_strafe->radio_in); } diff --git a/modules/PX4Firmware b/modules/PX4Firmware deleted file mode 160000 index 8048e54259..0000000000 --- a/modules/PX4Firmware +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 8048e542599a89acd72fff2fce831a8012201a96 diff --git a/modules/PX4NuttX b/modules/PX4NuttX deleted file mode 160000 index d48fa3072b..0000000000 --- a/modules/PX4NuttX +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d48fa3072b2396c489966c4ab10183ac7cf3dea9 diff --git a/modules/gbenchmark b/modules/gbenchmark deleted file mode 160000 index 006d23ccca..0000000000 --- a/modules/gbenchmark +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 006d23ccca1375a973b7fae0cc351cedb41b812a diff --git a/modules/uavcan b/modules/uavcan deleted file mode 160000 index 6dd432c974..0000000000 --- a/modules/uavcan +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 6dd432c9742c22e1dd1638c7f91cf937e4bdb2f1 diff --git a/modules/waf b/modules/waf deleted file mode 160000 index d2ade00ef8..0000000000 --- a/modules/waf +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d2ade00ef86f5024317ef48ae0e30cff51c8f3dd