diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2013-10-17 20:29:54 +0200 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2013-10-24 17:40:14 +0200 |
commit | a0ea0901b555b4c7732dbc2da22339d82f581e48 (patch) | |
tree | 59c6b4c26b82f9d1b6ab40a2511017bd953da4fb /src/modules/fw_att_control | |
parent | b21b9078e2d719bfd7af9580ac3b9b5957ef1d57 (diff) | |
download | px4-firmware-a0ea0901b555b4c7732dbc2da22339d82f581e48.tar.gz px4-firmware-a0ea0901b555b4c7732dbc2da22339d82f581e48.tar.bz2 px4-firmware-a0ea0901b555b4c7732dbc2da22339d82f581e48.zip |
wip, minor bugfixes in fw att control
Diffstat (limited to 'src/modules/fw_att_control')
-rw-r--r-- | src/modules/fw_att_control/fw_att_control_main.cpp | 8 | ||||
-rw-r--r-- | src/modules/fw_att_control/fw_att_control_params.c | 4 |
2 files changed, 7 insertions, 5 deletions
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp index 422e94ba1..bc9d6771b 100644 --- a/src/modules/fw_att_control/fw_att_control_main.cpp +++ b/src/modules/fw_att_control/fw_att_control_main.cpp @@ -673,7 +673,7 @@ FixedwingAttitudeControl::task_main() /* Run attitude controllers */ _roll_ctrl.control_attitude(roll_sp, _att.roll); - _pitch_ctrl.control_attitude(roll_sp, _att.roll, _att.pitch, airspeed); + _pitch_ctrl.control_attitude(pitch_sp, _att.roll, _att.pitch, airspeed); _yaw_ctrl.control_attitude(_att.roll, _att.pitch, speed_body_u,speed_body_w, _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate()); //runs last, because is depending on output of roll and pitch attitude @@ -709,9 +709,9 @@ FixedwingAttitudeControl::task_main() * only once available */ vehicle_rates_setpoint_s rates_sp; - rates_sp.roll = _roll_ctrl.get_desired_rate(); - rates_sp.pitch = _pitch_ctrl.get_desired_rate(); - rates_sp.yaw = _yaw_ctrl.get_desired_rate(); + rates_sp.roll = _roll_ctrl.get_desired_bodyrate(); + rates_sp.pitch = _pitch_ctrl.get_desired_bodyrate(); + rates_sp.yaw = _yaw_ctrl.get_desired_bodyrate(); rates_sp.timestamp = hrt_absolute_time(); diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c index 97aa275de..717608159 100644 --- a/src/modules/fw_att_control/fw_att_control_params.c +++ b/src/modules/fw_att_control/fw_att_control_params.c @@ -44,6 +44,8 @@ #include <systemlib/param/param.h> +//XXX resolve unclear naming of paramters: FW_P_D --> FW_PR_P + /* * Controller parameters, accessible via MAVLink * @@ -130,7 +132,7 @@ PARAM_DEFINE_FLOAT(FW_Y_P, 0); PARAM_DEFINE_FLOAT(FW_Y_I, 0); PARAM_DEFINE_FLOAT(FW_Y_IMAX, 15.0f); PARAM_DEFINE_FLOAT(FW_Y_D, 0); -PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 1); +PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 0); PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 9.0f); PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 12.0f); PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 18.0f); |