Browse Source

Sub: Update forward and strafe rc channels in the control mode files.

mission-4.1.18
jaxxzer 9 years ago committed by Andrew Tridgell
parent
commit
2f3aff7499
  1. 5
      ArduSub/control_acro.cpp
  2. 5
      ArduSub/control_althold.cpp
  3. 5
      ArduSub/control_stabilize.cpp

5
ArduSub/control_acro.cpp

@ -47,6 +47,11 @@ void Copter::acro_run() @@ -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);
}

5
ArduSub/control_althold.cpp

@ -158,4 +158,9 @@ void Copter::althold_run() @@ -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);
}

5
ArduSub/control_stabilize.cpp

@ -57,4 +57,9 @@ void Copter::stabilize_run() @@ -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);
}

Loading…
Cancel
Save