aboutsummaryrefslogtreecommitdiff
path: root/src/modules/multirotor_att_control
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/multirotor_att_control')
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c123
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c5
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.h5
3 files changed, 77 insertions, 56 deletions
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index 8ba3241ad..41a9f1df5 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -57,7 +57,8 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <drivers/drv_gyro.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
@@ -86,13 +87,15 @@ static bool motor_test_mode = false;
static orb_advert_t actuator_pub;
static orb_advert_t control_debug_pub;
-static struct vehicle_status_s state;
static int
mc_thread_main(int argc, char *argv[])
{
/* declare and safely initialize all structs */
- memset(&state, 0, sizeof(state));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
+ struct actuator_safety_s safety;
+ memset(&safety, 0, sizeof(safety));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
@@ -117,7 +120,8 @@ mc_thread_main(int argc, char *argv[])
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));
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
@@ -157,7 +161,9 @@ mc_thread_main(int argc, char *argv[])
/* store last control mode to detect mode switches */
bool flag_control_manual_enabled = false;
bool flag_control_attitude_enabled = false;
- bool flag_system_armed = false;
+ bool flag_armed = false;
+ bool flag_control_position_enabled = false;
+ bool flag_control_velocity_enabled = false;
/* store if yaw position or yaw speed has been changed */
bool control_yaw_position = true;
@@ -169,7 +175,6 @@ mc_thread_main(int argc, char *argv[])
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
float failsafe_throttle = 0.0f;
-
while (!thread_should_exit) {
/* wait for a sensor update, check for exit condition every 500 ms */
@@ -182,7 +187,6 @@ mc_thread_main(int argc, char *argv[])
} 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 */
@@ -200,10 +204,16 @@ mc_thread_main(int argc, char *argv[])
/* get a local copy of system state */
bool updated;
- orb_check(state_sub, &updated);
+ orb_check(control_mode_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
+ }
+
+ orb_check(safety_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
}
/* get a local copy of manual setpoint */
@@ -222,9 +232,8 @@ mc_thread_main(int argc, char *argv[])
/* 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) {
+ if (control_mode.flag_control_offboard_enabled) {
/* offboard inputs */
if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
rates_sp.roll = offboard_sp.p1;
@@ -247,20 +256,20 @@ mc_thread_main(int argc, char *argv[])
}
- } else if (state.flag_control_manual_enabled) {
-
- if (state.flag_control_attitude_enabled) {
-
+ } else if (control_mode.flag_control_manual_enabled) {
+ if (control_mode.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) {
+ if (control_mode.flag_control_attitude_enabled != flag_control_attitude_enabled ||
+ control_mode.flag_control_manual_enabled != flag_control_manual_enabled ||
+ safety.armed != flag_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 */
+/* XXX fix this */
+#if 0
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);
@@ -292,33 +301,35 @@ mc_thread_main(int argc, char *argv[])
rc_loss_first_time = false;
} else {
+#endif
rc_loss_first_time = true;
att_sp.roll_body = manual.roll;
att_sp.pitch_body = manual.pitch;
/* set attitude if arming */
- if (!flag_control_attitude_enabled && state.flag_system_armed) {
+ if (!flag_control_attitude_enabled && safety.armed) {
att_sp.yaw_body = att.yaw;
}
/* act if stabilization is active or if the (nonsense) direct pass through mode is set */
- if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS ||
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
-
- if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) {
- rates_sp.yaw = manual.yaw;
- control_yaw_position = false;
-
- } else {
- /*
- * This mode SHOULD be the default mode, which is:
- * VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS
- *
- * However, we fall back to this setting for all other (nonsense)
- * settings as well.
- */
-
+#warning fix this
+// if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS ||
+// state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+//
+// if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) {
+// rates_sp.yaw = manual.yaw;
+// control_yaw_position = false;
+//
+// } else {
+// /*
+// * This mode SHOULD be the default mode, which is:
+// * VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS
+// *
+// * However, we fall back to this setting for all other (nonsense)
+// * settings as well.
+// */
+//
/* only move setpoint if manual input is != 0 */
if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
rates_sp.yaw = manual.yaw;
@@ -333,16 +344,19 @@ mc_thread_main(int argc, char *argv[])
control_yaw_position = true;
}
- }
- }
+// }
+// }
att_sp.thrust = manual.throttle;
att_sp.timestamp = hrt_absolute_time();
+#if 0
}
+#endif
/* STEP 2: publish the controller output */
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+
if (motor_test_mode) {
printf("testmode");
att_sp.roll_body = 0.0f;
@@ -355,23 +369,24 @@ mc_thread_main(int argc, char *argv[])
}
} else {
+#warning fix this
/* manual rate inputs, from RC control or joystick */
- if (state.flag_control_rates_enabled &&
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
- 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_rates_enabled &&
+// state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
+// 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();
+// }
}
}
/** 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, control_yaw_position);
+ if (control_mode.flag_control_attitude_enabled) {
+ multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, &control_debug_pub, &control_debug);
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
}
@@ -400,10 +415,12 @@ mc_thread_main(int argc, char *argv[])
orb_publish(ORB_ID(vehicle_control_debug), control_debug_pub, &control_debug);
- /* 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 control_mode */
+ flag_control_attitude_enabled = control_mode.flag_control_attitude_enabled;
+ flag_control_manual_enabled = control_mode.flag_control_manual_enabled;
+ flag_control_position_enabled = control_mode.flag_control_position_enabled;
+ flag_control_velocity_enabled = control_mode.flag_control_velocity_enabled;
+ flag_armed = safety.armed;
perf_end(mc_loop_perf);
} /* end of poll call for attitude updates */
@@ -420,7 +437,7 @@ mc_thread_main(int argc, char *argv[])
close(att_sub);
- close(state_sub);
+ close(control_mode_sub);
close(manual_sub);
close(actuator_pub);
close(att_sp_pub);
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index 0dad10316..752f292e3 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
@@ -123,7 +123,8 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
}
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position)
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position,
+ const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug)
{
static uint64_t last_run = 0;
static uint64_t last_input = 0;
@@ -182,7 +183,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
/* control pitch (forward) output */
rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body ,
- att->pitch, att->pitchspeed, deltaT, NULL, NULL, NULL);
+ att->pitch, att->pitchspeed, deltaT, &control_debug->pitch_p, &control_debug->pitch_i, &control_debug->pitch_d);
/* control roll (left/right) output */
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body ,
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.h b/src/modules/multirotor_att_control/multirotor_attitude_control.h
index 2cf83e443..4e70a5103 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.h
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.h
@@ -50,8 +50,11 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_debug.h>
+
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position);
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position,
+ const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug);
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */