aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
diff options
context:
space:
mode:
authorTickTock- <TjckTock@gmail.com>2014-04-28 21:47:45 -0700
committerTickTock- <TjckTock@gmail.com>2014-04-28 21:47:45 -0700
commit31089a290ba089b2b5cbcc76ed677e3f401ffa36 (patch)
treedfa7cc73cfa9b4d1b52f801aa05f66429c0ffa41 /src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
parent269800b48c31d78fec900b4beaf3f655a8c18730 (diff)
downloadpx4-firmware-31089a290ba089b2b5cbcc76ed677e3f401ffa36.tar.gz
px4-firmware-31089a290ba089b2b5cbcc76ed677e3f401ffa36.tar.bz2
px4-firmware-31089a290ba089b2b5cbcc76ed677e3f401ffa36.zip
Replaces poshold/althold with posctrl/altctrl
Diffstat (limited to 'src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp42
1 files changed, 21 insertions, 21 deletions
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index d5a68e21f..024dd98ec 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -153,7 +153,7 @@ private:
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
/** manual control states */
- float _althold_hold_heading; /**< heading the system should hold in althold mode */
+ float _altctrl_hold_heading; /**< heading the system should hold in altctrl mode */
double _loiter_hold_lat;
double _loiter_hold_lon;
float _loiter_hold_alt;
@@ -1051,16 +1051,16 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.roll_reset_integral = true;
}
- } else if (0/* poshold mode enabled */) {
+ } else if (0/* posctrl mode enabled */) {
- /** POSHOLD FLIGHT **/
+ /** POSCTRL FLIGHT **/
- if (0/* switched from another mode to poshold */) {
- _althold_hold_heading = _att.yaw;
+ if (0/* switched from another mode to posctrl */) {
+ _altctrl_hold_heading = _att.yaw;
}
- if (0/* poshold on and manual control yaw non-zero */) {
- _althold_hold_heading = _att.yaw + _manual.yaw;
+ if (0/* posctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.yaw;
}
//XXX not used
@@ -1073,39 +1073,39 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// climb_out = true;
// }
- /* if in althold mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
// XXX check if ground speed undershoot should be applied here
- float althold_airspeed = _parameters.airspeed_min +
+ float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
_manual.throttle;
- _l1_control.navigate_heading(_althold_hold_heading, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
_tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- althold_airspeed,
+ altctrl_airspeed,
_airspeed.indicated_airspeed_m_s, eas2tas,
false, _parameters.pitch_limit_min,
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
_parameters.pitch_limit_min, _parameters.pitch_limit_max);
- } else if (0/* althold mode enabled */) {
+ } else if (0/* altctrl mode enabled */) {
- /** ALTHOLD FLIGHT **/
+ /** ALTCTRL FLIGHT **/
- if (0/* switched from another mode to althold */) {
- _althold_hold_heading = _att.yaw;
+ if (0/* switched from another mode to altctrl */) {
+ _altctrl_hold_heading = _att.yaw;
}
- if (0/* althold on and manual control yaw non-zero */) {
- _althold_hold_heading = _att.yaw + _manual.yaw;
+ if (0/* altctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.yaw;
}
- /* if in althold mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
// XXX check if ground speed undershoot should be applied here
- float althold_airspeed = _parameters.airspeed_min +
+ float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
_manual.throttle;
@@ -1124,11 +1124,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
climb_out = true;
}
- _l1_control.navigate_heading(_althold_hold_heading, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
_att_sp.roll_body = _manual.roll;
_att_sp.yaw_body = _manual.yaw;
_tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- althold_airspeed,
+ altctrl_airspeed,
_airspeed.indicated_airspeed_m_s, eas2tas,
climb_out, _parameters.pitch_limit_min,
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,