mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Sub: Apply deadzone by using norm_input_dz instead of norm_input
This commit is contained in:
parent
36f3cae535
commit
a3565c90b5
@ -49,8 +49,8 @@ void Sub::acro_run()
|
||||
|
||||
//control_in is range 0-1000
|
||||
//radio_in is raw pwm value
|
||||
motors.set_forward(channel_forward->norm_input());
|
||||
motors.set_lateral(channel_lateral->norm_input());
|
||||
motors.set_forward(channel_forward->norm_input_dz());
|
||||
motors.set_lateral(channel_lateral->norm_input_dz());
|
||||
}
|
||||
|
||||
|
||||
|
@ -160,6 +160,6 @@ void Sub::althold_run()
|
||||
|
||||
//control_in is range 0-1000
|
||||
//radio_in is raw pwm value
|
||||
motors.set_forward(channel_forward->norm_input());
|
||||
motors.set_lateral(channel_lateral->norm_input());
|
||||
motors.set_forward(channel_forward->norm_input_dz());
|
||||
motors.set_lateral(channel_lateral->norm_input_dz());
|
||||
}
|
||||
|
@ -27,10 +27,10 @@ void Sub::manual_run()
|
||||
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
motors.set_roll(channel_roll->norm_input()*0.67f);
|
||||
motors.set_pitch(channel_pitch->norm_input()*0.67f);
|
||||
motors.set_yaw(channel_yaw->norm_input()*0.67f);
|
||||
motors.set_roll(channel_roll->norm_input_dz()*0.67f);
|
||||
motors.set_pitch(channel_pitch->norm_input_dz()*0.67f);
|
||||
motors.set_yaw(channel_yaw->norm_input_dz()*0.67f);
|
||||
motors.set_throttle(channel_throttle->norm_input());
|
||||
motors.set_forward(channel_forward->norm_input()*0.67f);
|
||||
motors.set_lateral(channel_lateral->norm_input()*0.67f);
|
||||
motors.set_forward(channel_forward->norm_input_dz()*0.67f);
|
||||
motors.set_lateral(channel_lateral->norm_input_dz()*0.67f);
|
||||
}
|
||||
|
@ -78,6 +78,6 @@ void Sub::stabilize_run()
|
||||
|
||||
//control_in is range -1000-1000
|
||||
//radio_in is raw pwm value
|
||||
motors.set_forward(channel_forward->norm_input());
|
||||
motors.set_lateral(channel_lateral->norm_input());
|
||||
motors.set_forward(channel_forward->norm_input_dz());
|
||||
motors.set_lateral(channel_lateral->norm_input_dz());
|
||||
}
|
||||
|
@ -59,6 +59,6 @@ void Sub::surface_run()
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// pilot has control for repositioning
|
||||
motors.set_forward(channel_forward->norm_input());
|
||||
motors.set_lateral(channel_lateral->norm_input());
|
||||
motors.set_forward(channel_forward->norm_input_dz());
|
||||
motors.set_lateral(channel_lateral->norm_input_dz());
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user