mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
minor changes
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2420 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ee67f964a1
commit
0d1f184076
@ -39,6 +39,7 @@
|
|||||||
#define GPS_PROTOCOL_MTK 4
|
#define GPS_PROTOCOL_MTK 4
|
||||||
#define GPS_PROTOCOL_HIL 5
|
#define GPS_PROTOCOL_HIL 5
|
||||||
#define GPS_PROTOCOL_MTK16 6
|
#define GPS_PROTOCOL_MTK16 6
|
||||||
|
#define GPS_PROTOCOL_AUTO 7
|
||||||
|
|
||||||
// Radio channels
|
// Radio channels
|
||||||
// Note channels are from 0!
|
// Note channels are from 0!
|
||||||
|
@ -56,6 +56,14 @@ void output_motors_armed()
|
|||||||
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
||||||
|
|
||||||
|
// limit output so motors don't stop
|
||||||
|
motor_out[CH_1] = max(motor_out[CH_1], out_min);
|
||||||
|
motor_out[CH_2] = max(motor_out[CH_2], out_min);
|
||||||
|
motor_out[CH_3] = max(motor_out[CH_3], out_min);
|
||||||
|
motor_out[CH_4] = max(motor_out[CH_4], out_min);
|
||||||
|
motor_out[CH_7] = max(motor_out[CH_7], out_min);
|
||||||
|
motor_out[CH_8] = max(motor_out[CH_8], out_min);
|
||||||
|
|
||||||
// Send commands to motors
|
// Send commands to motors
|
||||||
if(g.rc_3.servo_out > 0){
|
if(g.rc_3.servo_out > 0){
|
||||||
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
||||||
|
Loading…
Reference in New Issue
Block a user