aboutsummaryrefslogtreecommitdiff
path: root/apps/multirotor_att_control/multirotor_att_control_main.c
diff options
context:
space:
mode:
authorJulian Oes <joes@student.ethz.ch>2012-11-15 11:55:55 -0800
committerJulian Oes <joes@student.ethz.ch>2012-11-15 11:55:55 -0800
commit33e750602ab384069b08ca17ca6589c08177f7a6 (patch)
tree8f2dbfe7779fc74436ea4ba243e2929c09d5b2ac /apps/multirotor_att_control/multirotor_att_control_main.c
parentb7c6a11e6739d217e5df1e79b7f80399ff1fd8f8 (diff)
parent3016ae72a3b3b7d7bf1df937fd62a14f53eace6f (diff)
downloadpx4-firmware-33e750602ab384069b08ca17ca6589c08177f7a6.tar.gz
px4-firmware-33e750602ab384069b08ca17ca6589c08177f7a6.tar.bz2
px4-firmware-33e750602ab384069b08ca17ca6589c08177f7a6.zip
Merge remote-tracking branch 'upstream/master' into io
Fixed Conflicts: apps/multirotor_att_control/multirotor_att_control_main.c rc loss failsafe throttle tested
Diffstat (limited to 'apps/multirotor_att_control/multirotor_att_control_main.c')
-rw-r--r--apps/multirotor_att_control/multirotor_att_control_main.c319
1 files changed, 165 insertions, 154 deletions
diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c
index de3a4440b..d2de1a787 100644
--- a/apps/multirotor_att_control/multirotor_att_control_main.c
+++ b/apps/multirotor_att_control/multirotor_att_control_main.c
@@ -65,6 +65,7 @@
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/parameter_update.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
@@ -107,6 +108,7 @@ mc_thread_main(int argc, char *argv[])
/* subscribe to attitude, motor setpoints and system state */
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int param_sub = orb_subscribe(ORB_ID(parameter_update));
int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
@@ -121,7 +123,10 @@ mc_thread_main(int argc, char *argv[])
* rate-limit the attitude subscription to 200Hz to pace our loop
* orb_set_interval(att_sub, 5);
*/
- struct pollfd fds = { .fd = att_sub, .events = POLLIN };
+ struct pollfd fds[2] = {
+ { .fd = att_sub, .events = POLLIN },
+ { .fd = param_sub, .events = POLLIN }
+ };
/* publish actuator controls */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
@@ -134,7 +139,9 @@ mc_thread_main(int argc, char *argv[])
int rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
/* register the perf counter */
- perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "multirotor_att_control");
+ perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "multirotor_att_control_runtime");
+ perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "multirotor_att_control_interval");
+ perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "multirotor_att_control_err");
/* welcome user */
printf("[multirotor_att_control] starting\n");
@@ -143,7 +150,6 @@ mc_thread_main(int argc, char *argv[])
bool flag_control_manual_enabled = false;
bool flag_control_attitude_enabled = false;
bool flag_system_armed = false;
- bool man_yaw_zero_once = false;
/* prepare the handle for the failsafe throttle */
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
@@ -152,180 +158,185 @@ mc_thread_main(int argc, char *argv[])
while (!thread_should_exit) {
/* wait for a sensor update, check for exit condition every 500 ms */
- poll(&fds, 1, 500);
+ int ret = poll(fds, 2, 500);
+
+ if (ret < 0) {
+ /* poll error, count it in perf */
+ perf_count(mc_err_perf);
+ } else if (ret == 0) {
+ /* no return value, ignore */
+ } else {
+
+ /* only update parameters if they changed */
+ if (fds[1].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), param_sub, &update);
+
+ /* update parameters */
+ // XXX no params here yet
+ }
- perf_begin(mc_loop_perf);
+ /* only run controller if attitude changed */
+ if (fds[0].revents & POLLIN) {
- /* get a local copy of system state */
- bool updated;
- orb_check(state_sub, &updated);
- if (updated) {
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
- }
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
- /* get a local copy of attitude setpoint */
- orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp);
- /* get a local copy of rates setpoint */
- orb_check(setpoint_sub, &updated);
- if (updated) {
- orb_copy(ORB_ID(offboard_control_setpoint), setpoint_sub, &offboard_sp);
- }
- /* get a local copy of the current sensor values */
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
-
-
- /** STEP 1: Define which input is the dominating control input */
- if (state.flag_control_offboard_enabled) {
- /* offboard inputs */
- if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
- rates_sp.roll = offboard_sp.p1;
- rates_sp.pitch = offboard_sp.p2;
- rates_sp.yaw = offboard_sp.p3;
- if (state.offboard_control_signal_lost) {
- /* give up in rate mode on signal loss */
- rates_sp.thrust = 0.0f;
- } else {
- /* no signal loss, normal throttle */
- rates_sp.thrust = offboard_sp.p4;
+ perf_begin(mc_loop_perf);
+
+ /* get a local copy of system state */
+ bool updated;
+ orb_check(state_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_status), state_sub, &state);
+ }
+ /* get a local copy of manual setpoint */
+ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
+ /* get a local copy of attitude */
+ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+ /* get a local copy of attitude setpoint */
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp);
+ /* get a local copy of rates setpoint */
+ orb_check(setpoint_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(offboard_control_setpoint), setpoint_sub, &offboard_sp);
+ }
+ /* get a local copy of the current sensor values */
+ orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
+
+
+ /** STEP 1: Define which input is the dominating control input */
+ if (state.flag_control_offboard_enabled) {
+ /* offboard inputs */
+ if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
+ rates_sp.roll = offboard_sp.p1;
+ rates_sp.pitch = offboard_sp.p2;
+ rates_sp.yaw = offboard_sp.p3;
+ rates_sp.thrust = offboard_sp.p4;
+ // printf("thrust_rate=%8.4f\n",offboard_sp.p4);
+ rates_sp.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
+ } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
+ att_sp.roll_body = offboard_sp.p1;
+ att_sp.pitch_body = offboard_sp.p2;
+ att_sp.yaw_body = offboard_sp.p3;
+ att_sp.thrust = offboard_sp.p4;
+ // printf("thrust_att=%8.4f\n",offboard_sp.p4);
+ att_sp.timestamp = hrt_absolute_time();
+ /* STEP 2: publish the result to the vehicle actuators */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ }
+
+ /* decide wether we want rate or position input */
}
-// printf("thrust_rate=%8.4f\n",offboard_sp.p4);
+ else if (state.flag_control_manual_enabled) {
+
+ /* manual inputs, from RC control or joystick */
+ if (state.flag_control_rates_enabled && !state.flag_control_attitude_enabled) {
+ rates_sp.roll = manual.roll;
+
+ rates_sp.pitch = manual.pitch;
+ rates_sp.yaw = manual.yaw;
+ rates_sp.thrust = manual.throttle;
rates_sp.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
- } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
- att_sp.roll_body = offboard_sp.p1;
- att_sp.pitch_body = offboard_sp.p2;
- att_sp.yaw_body = offboard_sp.p3;
-
- /* check if control signal is lost */
- if (state.offboard_control_signal_lost) {
- /* set failsafe thrust */
+ }
+
+ if (state.flag_control_attitude_enabled) {
+
+ /* initialize to current yaw if switching to manual or att control */
+ if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
+ state.flag_control_manual_enabled != flag_control_manual_enabled ||
+ state.flag_system_armed != flag_system_armed) {
+ att_sp.yaw_body = att.yaw;
+ }
+
+ static bool rc_loss_first_time = true;
+
+ /* if the RC signal is lost, try to stay level and go slowly back down to ground */
+ if(state.rc_signal_lost) {
+ /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
param_get(failsafe_throttle_handle, &failsafe_throttle);
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
att_sp.thrust = failsafe_throttle;
+
+ /* keep current yaw, do not attempt to go to north orientation,
+ * since if the pilot regains RC control, he will be lost regarding
+ * the current orientation.
+ */
+ if (rc_loss_first_time)
+ att_sp.yaw_body = att.yaw;
+
+ // XXX hard-limit it to prevent ballistic mishaps - this is just supposed to
+ // slow a crash down, not actually keep the system in-air.
+
+ rc_loss_first_time = false;
+
} else {
- /* no signal loss, normal throttle */
- att_sp.thrust = offboard_sp.p4;
+ rc_loss_first_time = true;
+
+ att_sp.roll_body = manual.roll;
+ att_sp.pitch_body = manual.pitch;
+
+ /* only move setpoint if manual input is != 0 */
+ // XXX turn into param
+ if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
+ att_sp.yaw_body = att_sp.yaw_body + manual.yaw * 0.0025f;
+ } else if (manual.throttle <= 0.3f) {
+ att_sp.yaw_body = att.yaw;
+ }
+ att_sp.thrust = manual.throttle;
+ att_sp.timestamp = hrt_absolute_time();
}
-
-// printf("thrust_att=%8.4f\n",offboard_sp.p4);
+ }
+ /* STEP 2: publish the result to the vehicle actuators */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+
+ if (motor_test_mode) {
+ printf("testmode");
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
+ att_sp.yaw_body = 0.0f;
+ att_sp.thrust = 0.1f;
att_sp.timestamp = hrt_absolute_time();
/* STEP 2: publish the result to the vehicle actuators */
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
}
- /* decide wether we want rate or position input */
}
- else if (state.flag_control_manual_enabled) {
- /* manual inputs, from RC control or joystick */
-
- if (state.flag_control_rates_enabled && !state.flag_control_attitude_enabled) {
- rates_sp.roll = manual.roll;
-
- rates_sp.pitch = manual.pitch;
- rates_sp.yaw = manual.yaw;
- rates_sp.thrust = manual.throttle;
- rates_sp.timestamp = hrt_absolute_time();
- }
-
- if (state.flag_control_attitude_enabled) {
- /* initialize to current yaw if switching to manual or att control */
- if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
- state.flag_control_manual_enabled != flag_control_manual_enabled ||
- state.flag_system_armed != flag_system_armed) {
- att_sp.yaw_body = att.yaw;
+ /** STEP 3: Identify the controller setup to run and set up the inputs correctly */
+ if (state.flag_control_attitude_enabled) {
+ multirotor_control_attitude(&att_sp, &att, &rates_sp, NULL);
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
}
- att_sp.roll_body = manual.roll;
- att_sp.pitch_body = manual.pitch;
-
- /* only move setpoint if manual input is != 0 */
- // XXX turn into param
- if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
- att_sp.yaw_body = att_sp.yaw_body + manual.yaw * 0.0025f;
- } else if (manual.throttle <= 0.3f) {
- att_sp.yaw_body = att.yaw;
- }
- att_sp.thrust = manual.throttle;
-
- // XXX disable this for now until its better checked
-
- static bool rc_loss_first_time = true;
- /* if the RC signal is lost, try to stay level and go slowly back down to ground */
- if(state.rc_signal_lost) {
- /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
- param_get(failsafe_throttle_handle, &failsafe_throttle);
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
-
- /* keep current yaw, do not attempt to go to north orientation,
- * since if the pilot regains RC control, he will be lost regarding
- * the current orientation.
- */
-
- if (rc_loss_first_time)
- att_sp.yaw_body = att.yaw;
- // XXX hard-limit it to prevent ballistic mishaps - this is just supposed to
- // slow a crash down, not actually keep the system in-air.
- att_sp.thrust = failsafe_throttle;
- rc_loss_first_time = false;
- } else {
- rc_loss_first_time = true;
- }
-
- att_sp.timestamp = hrt_absolute_time();
- }
- /* STEP 2: publish the result to the vehicle actuators */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
-
- if (motor_test_mode) {
- printf("testmode");
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
- att_sp.yaw_body = 0.0f;
- att_sp.thrust = 0.1f;
- att_sp.timestamp = hrt_absolute_time();
- /* STEP 2: publish the result to the vehicle actuators */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- }
-
- }
-
- /** STEP 3: Identify the controller setup to run and set up the inputs correctly */
- if (state.flag_control_attitude_enabled) {
- multirotor_control_attitude(&att_sp, &att, &rates_sp, NULL);
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
- }
-
+ /* measure in what intervals the controller runs */
+ perf_count(mc_interval_perf);
- if (state.flag_control_rates_enabled) {
+ float gyro[3];
- float gyro[3];
-
- /* get current rate setpoint */
- bool rates_sp_valid = false;
- orb_check(rates_sp_sub, &rates_sp_valid);
- if (rates_sp_valid) {
- orb_copy(ORB_ID(vehicle_rates_setpoint), rates_sp_sub, &rates_sp);
- }
+ /* get current rate setpoint */
+ bool rates_sp_valid = false;
+ orb_check(rates_sp_sub, &rates_sp_valid);
+ if (rates_sp_valid) {
+ orb_copy(ORB_ID(vehicle_rates_setpoint), rates_sp_sub, &rates_sp);
+ }
- /* apply controller */
- gyro[0] = att.rollspeed;
- gyro[1] = att.pitchspeed;
- gyro[2] = att.yawspeed;
+ /* apply controller */
+ gyro[0] = att.rollspeed;
+ gyro[1] = att.pitchspeed;
+ gyro[2] = att.yawspeed;
- multirotor_control_rates(&rates_sp, gyro, &actuators);
- orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- }
+ multirotor_control_rates(&rates_sp, gyro, &actuators);
+ orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- /* update state */
- flag_control_attitude_enabled = state.flag_control_attitude_enabled;
- flag_control_manual_enabled = state.flag_control_manual_enabled;
- flag_system_armed = state.flag_system_armed;
+ /* update state */
+ flag_control_attitude_enabled = state.flag_control_attitude_enabled;
+ flag_control_manual_enabled = state.flag_control_manual_enabled;
+ flag_system_armed = state.flag_system_armed;
- perf_end(mc_loop_perf);
+ perf_end(mc_loop_perf);
+ } /* end of poll call for attitude updates */
+ } /* end of poll return value check */
}
printf("[multirotor att control] stopping, disarming motors.\n");