mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Copter: change multirotor comments to multicopter
No functional change
This commit is contained in:
parent
1b68d0eead
commit
35a924703f
@ -84,7 +84,7 @@ void Copter::althold_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // Multicopter do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif // HELI_FRAME
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
@ -119,7 +119,7 @@ void Copter::althold_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // Multicopter do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
#endif
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
|
@ -119,7 +119,7 @@ void Copter::auto_takeoff_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
@ -172,7 +172,7 @@ void Copter::auto_wp_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
// clear i term when we're taking off
|
||||
@ -236,7 +236,7 @@ void Copter::auto_spline_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
// clear i term when we're taking off
|
||||
@ -309,7 +309,7 @@ void Copter::auto_land_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
// set target to current position
|
||||
@ -481,7 +481,7 @@ void Copter::auto_loiter_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
return;
|
||||
|
@ -41,7 +41,7 @@ void Copter::brake_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(0)-throttle_average);
|
||||
|
@ -41,7 +41,7 @@ void Copter::circle_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
pos_control.set_alt_target_to_current_alt();
|
||||
|
@ -167,7 +167,7 @@ void Copter::guided_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
// To-Do: handle take-offs - these may not only be immediately after auto_armed becomes true
|
||||
@ -211,7 +211,7 @@ void Copter::guided_takeoff_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
|
@ -58,7 +58,7 @@ void Copter::land_gps_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
wp_nav.init_loiter_target();
|
||||
@ -151,7 +151,7 @@ void Copter::land_nogps_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
|
||||
|
@ -81,7 +81,7 @@ void Copter::loiter_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif // HELI_FRAME
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
@ -119,7 +119,7 @@ void Copter::loiter_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
#endif
|
||||
|
@ -139,7 +139,7 @@ void Copter::rtl_climb_return_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
@ -201,7 +201,7 @@ void Copter::rtl_loiterathome_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
@ -277,7 +277,7 @@ void Copter::rtl_descent_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
// set target to current position
|
||||
@ -345,7 +345,7 @@ void Copter::rtl_land_run()
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multirotors do not stabilize roll/pitch/yaw when disarmed
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
// set target to current position
|
||||
|
Loading…
Reference in New Issue
Block a user