aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_att_control/fw_att_control_main.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:59:58 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:59:58 +0100
commitb376316fb19e497f76512a0353183936396e769d (patch)
tree428bcd6ee1926b57a64cc47d903273225fb56ba4 /src/modules/fw_att_control/fw_att_control_main.cpp
parent25af4b266ca48b183a1ad375856396f67d6ab30f (diff)
parentd8eefa30538331fde7e5ce79fef4e04dc62664bc (diff)
downloadpx4-firmware-b376316fb19e497f76512a0353183936396e769d.tar.gz
px4-firmware-b376316fb19e497f76512a0353183936396e769d.tar.bz2
px4-firmware-b376316fb19e497f76512a0353183936396e769d.zip
Merge remote-tracking branch 'upstream/isvtol' into dev_ros
Conflicts: src/modules/mc_att_control/mc_att_control_main.cpp src/modules/uORB/topics/vehicle_status.h
Diffstat (limited to 'src/modules/fw_att_control/fw_att_control_main.cpp')
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp37
1 files changed, 16 insertions, 21 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 0025aae7f..a0f74517c 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -195,8 +195,6 @@ private:
float man_roll_max; /**< Max Roll in rad */
float man_pitch_max; /**< Max Pitch in rad */
- param_t autostart_id; /* indicates which airframe is used */
-
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -237,7 +235,6 @@ private:
param_t man_roll_max;
param_t man_pitch_max;
- param_t autostart_id; /* indicates which airframe is used */
} _parameter_handles; /**< handles for interesting parameters */
@@ -339,6 +336,9 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_actuators_0_pub(-1),
_actuators_2_pub(-1),
+ _rates_sp_id(ORB_ID(vehicle_rates_setpoint)),
+ _actuators_id(ORB_ID(actuator_controls_0)),
+
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
_nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control nonfinite input")),
@@ -397,19 +397,8 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_parameter_handles.man_roll_max = param_find("FW_MAN_R_MAX");
_parameter_handles.man_pitch_max = param_find("FW_MAN_P_MAX");
- _parameter_handles.autostart_id = param_find("SYS_AUTOSTART");
-
/* fetch initial parameter values */
parameters_update();
- // set correct uORB ID, depending on if vehicle is VTOL or not
- if (_parameters.autostart_id >= 13000 && _parameters.autostart_id <= 13999) { /* VTOL airframe?*/
- _rates_sp_id = ORB_ID(fw_virtual_rates_setpoint);
- _actuators_id = ORB_ID(actuator_controls_virtual_fw);
- }
- else {
- _rates_sp_id = ORB_ID(vehicle_rates_setpoint);
- _actuators_id = ORB_ID(actuator_controls_0);
- }
}
FixedwingAttitudeControl::~FixedwingAttitudeControl()
@@ -484,8 +473,6 @@ FixedwingAttitudeControl::parameters_update()
_parameters.man_roll_max = math::radians(_parameters.man_roll_max);
_parameters.man_pitch_max = math::radians(_parameters.man_pitch_max);
- param_get(_parameter_handles.autostart_id, &_parameters.autostart_id);
-
/* pitch control parameters */
_pitch_ctrl.set_time_constant(_parameters.tconst);
_pitch_ctrl.set_k_p(_parameters.p_p);
@@ -601,6 +588,14 @@ FixedwingAttitudeControl::vehicle_status_poll()
if (vehicle_status_updated) {
orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
+ /* set correct uORB ID, depending on if vehicle is VTOL or not */
+ if (_vehicle_status.is_vtol) {
+ _rates_sp_id = ORB_ID(fw_virtual_rates_setpoint);
+ _actuators_id = ORB_ID(actuator_controls_virtual_fw);
+ } else {
+ _rates_sp_id = ORB_ID(vehicle_rates_setpoint);
+ _actuators_id = ORB_ID(actuator_controls_0);
+ }
}
}
@@ -701,11 +696,11 @@ FixedwingAttitudeControl::task_main()
/* load local copies */
orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
- if (_parameters.autostart_id >= 13000
- && _parameters.autostart_id <= 13999) { //vehicle type is VTOL, need to modify attitude!
- /* The following modification to the attitude is vehicle specific and in this case applies
- to tail-sitter models !!!
-
+ if (_vehicle_status.is_vtol) {
+ /* vehicle type is VTOL, need to modify attitude!
+ * The following modification to the attitude is vehicle specific and in this case applies
+ * to tail-sitter models !!!
+ *
* Since the VTOL airframe is initialized as a multicopter we need to
* modify the estimated attitude for the fixed wing operation.
* Since the neutral position of the vehicle in fixed wing mode is -90 degrees rotated around