aboutsummaryrefslogtreecommitdiff
path: root/src/modules/multirotor_att_control
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-08-16 13:23:33 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-08-16 13:23:33 +0200
commitf78666e0c8afd1fc8ac74f4cf2acc79ebe8b8476 (patch)
tree100ac05749e5c899d264de1d129d6d98935b2491 /src/modules/multirotor_att_control
parent3f9f1d60e03f501209deb6c7532c37dfb786f343 (diff)
parenta013fc5d0b28cd72f41a28c8229c2d7ab99965f4 (diff)
downloadpx4-firmware-f78666e0c8afd1fc8ac74f4cf2acc79ebe8b8476.tar.gz
px4-firmware-f78666e0c8afd1fc8ac74f4cf2acc79ebe8b8476.tar.bz2
px4-firmware-f78666e0c8afd1fc8ac74f4cf2acc79ebe8b8476.zip
Merge branch 'seatbelt_multirotor' into seatbelt_multirotor_new
WIP, TODO fixedwing
Diffstat (limited to 'src/modules/multirotor_att_control')
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c171
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c46
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.h5
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.c17
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.h4
5 files changed, 134 insertions, 109 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 20502c0ea..7014d22c4 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -58,13 +58,11 @@
#include <uORB/uORB.h>
#include <drivers/drv_gyro.h>
#include <uORB/topics/vehicle_control_mode.h>
-#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_control_debug.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
@@ -84,18 +82,12 @@ static bool thread_should_exit;
static int mc_task;
static bool motor_test_mode = false;
-static orb_advert_t actuator_pub;
-static orb_advert_t control_debug_pub;
-
-
static int
mc_thread_main(int argc, char *argv[])
{
/* declare and safely initialize all structs */
struct vehicle_control_mode_s control_mode;
memset(&control_mode, 0, sizeof(control_mode));
- struct actuator_armed_s armed;
- memset(&armed, 0, sizeof(armed));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
@@ -112,16 +104,12 @@ mc_thread_main(int argc, char *argv[])
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
- struct vehicle_control_debug_s control_debug;
- memset(&control_debug, 0, sizeof(control_debug));
-
/* 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 control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
@@ -142,10 +130,8 @@ mc_thread_main(int argc, char *argv[])
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
actuators.control[i] = 0.0f;
}
-
- control_debug_pub = orb_advertise(ORB_ID(vehicle_control_debug), &control_debug);
- actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
+ orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
orb_advert_t rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
int rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
@@ -161,20 +147,18 @@ 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_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;
/* store if we stopped a yaw movement */
- bool first_time_after_yaw_speed_control = true;
+ bool reset_yaw_sp = true;
/* prepare the handle for the failsafe throttle */
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 */
@@ -187,6 +171,7 @@ 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 */
@@ -210,12 +195,6 @@ mc_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
}
- orb_check(armed_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
- }
-
/* get a local copy of manual setpoint */
orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
/* get a local copy of attitude */
@@ -232,6 +211,7 @@ 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 (control_mode.flag_control_offboard_enabled) {
/* offboard inputs */
@@ -256,50 +236,90 @@ mc_thread_main(int argc, char *argv[])
}
- } else if (control_mode.flag_control_manual_enabled) {
+ } else if (control_mode.flag_control_manual_enabled) {
+ /* direct manual input */
if (control_mode.flag_control_attitude_enabled) {
+ /* control attitude, update attitude setpoint depending on mode */
/* initialize to current yaw if switching to manual or att control */
if (control_mode.flag_control_attitude_enabled != flag_control_attitude_enabled ||
- control_mode.flag_control_manual_enabled != flag_control_manual_enabled ||
- armed.armed != flag_armed) {
+ control_mode.flag_control_manual_enabled != flag_control_manual_enabled) {
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 (control_mode.failsave_highlevel) {
+ if (!control_mode.flag_control_position_enabled) {
+ /* Don't reset attitude setpoint in position control mode, it's handled by position controller. */
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
+
+ if (!control_mode.flag_control_altitude_enabled) {
+ /* Don't touch throttle in modes with altitude hold, it's handled by position controller.
+ *
+ * Only go to failsafe throttle if last known throttle was
+ * high enough to create some lift to make hovering state likely.
+ *
+ * This is to prevent that someone landing, but not disarming his
+ * multicopter (throttle = 0) does not make it jump up in the air
+ * if shutting down his remote.
+ */
+ if (isfinite(manual.throttle) && manual.throttle > 0.2f) {
+ /* 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.thrust = failsafe_throttle;
+
+ } else {
+ att_sp.thrust = 0.0f;
+ }
+ }
+ }
- 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 && armed.armed) {
- att_sp.yaw_body = att.yaw;
- }
+ /* 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;
- /* only move setpoint if manual input is != 0 */
- if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.1f) {
- rates_sp.yaw = manual.yaw;
- control_yaw_position = false;
- first_time_after_yaw_speed_control = true;
+ rc_loss_first_time = false;
} else {
- if (first_time_after_yaw_speed_control) {
- att_sp.yaw_body = att.yaw;
- first_time_after_yaw_speed_control = false;
- }
+ rc_loss_first_time = true;
- control_yaw_position = true;
- }
+ /* control yaw in all manual / assisted modes */
+ /* set yaw if arming or switching to attitude stabilized mode */
+ if (!flag_control_attitude_enabled) {
+ reset_yaw_sp = true;
+ }
- att_sp.thrust = manual.throttle;
- att_sp.timestamp = hrt_absolute_time();
+ /* only move setpoint if manual input is != 0 */
+ if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) { // TODO use landed status instead of throttle
+ rates_sp.yaw = manual.yaw;
+ control_yaw_position = false;
+ reset_yaw_sp = true;
+
+ } else {
+ if (reset_yaw_sp) {
+ att_sp.yaw_body = att.yaw;
+ reset_yaw_sp = false;
+ }
+ control_yaw_position = true;
+ }
- /* STEP 2: publish the controller output */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ if (!control_mode.flag_control_position_enabled) {
+ /* don't update attitude setpoint in position control mode */
+ att_sp.roll_body = manual.roll;
+ att_sp.pitch_body = manual.pitch;
+ if (!control_mode.flag_control_position_enabled) {
+ /* don't set throttle in altitude hold modes */
+ att_sp.thrust = manual.throttle;
+ }
+ }
+ att_sp.timestamp = hrt_absolute_time();
+ }
if (motor_test_mode) {
printf("testmode");
@@ -308,31 +328,26 @@ mc_thread_main(int argc, char *argv[])
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);
}
- } else {
+ /* STEP 2: publish the controller output */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- //XXX TODO add acro mode here
-
- /* 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();
-// }
+ } else {
+ /* manual rate inputs (ACRO), from RC control or joystick */
+ if (control_mode.flag_control_rates_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();
+ }
}
-
}
/** STEP 3: Identify the controller setup to run and set up the inputs correctly */
if (control_mode.flag_control_attitude_enabled) {
- multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, &control_debug_pub, &control_debug);
+ multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position);
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
}
@@ -340,8 +355,7 @@ mc_thread_main(int argc, char *argv[])
/* measure in what intervals the controller runs */
perf_count(mc_interval_perf);
- float rates[3];
- float rates_acc[3];
+ float gyro[3];
/* get current rate setpoint */
bool rates_sp_valid = false;
@@ -352,21 +366,16 @@ mc_thread_main(int argc, char *argv[])
}
/* apply controller */
- rates[0] = att.rollspeed;
- rates[1] = att.pitchspeed;
- rates[2] = att.yawspeed;
+ gyro[0] = att.rollspeed;
+ gyro[1] = att.pitchspeed;
+ gyro[2] = att.yawspeed;
- multirotor_control_rates(&rates_sp, rates, &actuators, &control_debug_pub, &control_debug);
+ multirotor_control_rates(&rates_sp, gyro, &actuators);
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- orb_publish(ORB_ID(vehicle_control_debug), control_debug_pub, &control_debug);
-
- /* update control_mode */
+ /* update state */
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 = armed.armed;
perf_end(mc_loop_perf);
} /* end of poll call for attitude updates */
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index 083311674..8f19c6a4b 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
@@ -65,29 +65,50 @@
PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
+//PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
+//PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
PARAM_DEFINE_FLOAT(MC_ATT_P, 0.2f);
PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
PARAM_DEFINE_FLOAT(MC_ATT_D, 0.05f);
+//PARAM_DEFINE_FLOAT(MC_ATT_AWU, 0.05f);
+//PARAM_DEFINE_FLOAT(MC_ATT_LIM, 0.4f);
+
+//PARAM_DEFINE_FLOAT(MC_ATT_XOFF, 0.0f);
+//PARAM_DEFINE_FLOAT(MC_ATT_YOFF, 0.0f);
struct mc_att_control_params {
float yaw_p;
float yaw_i;
float yaw_d;
+ //float yaw_awu;
+ //float yaw_lim;
float att_p;
float att_i;
float att_d;
+ //float att_awu;
+ //float att_lim;
+
+ //float att_xoff;
+ //float att_yoff;
};
struct mc_att_control_param_handles {
param_t yaw_p;
param_t yaw_i;
param_t yaw_d;
+ //param_t yaw_awu;
+ //param_t yaw_lim;
param_t att_p;
param_t att_i;
param_t att_d;
+ //param_t att_awu;
+ //param_t att_lim;
+
+ //param_t att_xoff;
+ //param_t att_yoff;
};
/**
@@ -109,10 +130,17 @@ static int parameters_init(struct mc_att_control_param_handles *h)
h->yaw_p = param_find("MC_YAWPOS_P");
h->yaw_i = param_find("MC_YAWPOS_I");
h->yaw_d = param_find("MC_YAWPOS_D");
+ //h->yaw_awu = param_find("MC_YAWPOS_AWU");
+ //h->yaw_lim = param_find("MC_YAWPOS_LIM");
h->att_p = param_find("MC_ATT_P");
h->att_i = param_find("MC_ATT_I");
h->att_d = param_find("MC_ATT_D");
+ //h->att_awu = param_find("MC_ATT_AWU");
+ //h->att_lim = param_find("MC_ATT_LIM");
+
+ //h->att_xoff = param_find("MC_ATT_XOFF");
+ //h->att_yoff = param_find("MC_ATT_YOFF");
return OK;
}
@@ -122,17 +150,23 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
param_get(h->yaw_p, &(p->yaw_p));
param_get(h->yaw_i, &(p->yaw_i));
param_get(h->yaw_d, &(p->yaw_d));
+ //param_get(h->yaw_awu, &(p->yaw_awu));
+ //param_get(h->yaw_lim, &(p->yaw_lim));
param_get(h->att_p, &(p->att_p));
param_get(h->att_i, &(p->att_i));
param_get(h->att_d, &(p->att_d));
+ //param_get(h->att_awu, &(p->att_awu));
+ //param_get(h->att_lim, &(p->att_lim));
+
+ //param_get(h->att_xoff, &(p->att_xoff));
+ //param_get(h->att_yoff, &(p->att_yoff));
return OK;
}
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 orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug)
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position)
{
static uint64_t last_run = 0;
static uint64_t last_input = 0;
@@ -173,7 +207,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
/* apply parameters */
pid_set_parameters(&pitch_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
- pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
+ pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
}
/* reset integral if on ground */
@@ -187,13 +221,11 @@ 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, &control_debug->pitch_p, &control_debug->pitch_i, &control_debug->pitch_d);
+ att->pitch, att->pitchspeed, deltaT);
/* control roll (left/right) output */
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body ,
- att->roll, att->rollspeed, deltaT, NULL, NULL, NULL);
-
- // printf("rates_sp: %4.4f, att setpoint: %4.4f\n, pitch: %4.4f, pitchspeed: %4.4f, dT: %4.4f", rates_sp->pitch, att_sp->pitch_body, att->pitch, att->pitchspeed, deltaT);
+ att->roll, att->rollspeed, deltaT);
if (control_yaw_position) {
/* control yaw rate */
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.h b/src/modules/multirotor_att_control/multirotor_attitude_control.h
index 6dd5b39fd..e78f45c47 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.h
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.h
@@ -58,11 +58,8 @@
#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 orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug);
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position);
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.c b/src/modules/multirotor_att_control/multirotor_rate_control.c
index ee8c37580..e58d357d5 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.c
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.c
@@ -58,9 +58,6 @@
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-
-
PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.0f); /* same on Flamewheel */
PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
@@ -155,8 +152,7 @@ static int parameters_update(const struct mc_rate_control_param_handles *h, stru
}
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[], struct actuator_controls_s *actuators,
- const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug)
+ const float rates[], struct actuator_controls_s *actuators)
{
static uint64_t last_run = 0;
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
@@ -176,13 +172,8 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
static struct mc_rate_control_params p;
static struct mc_rate_control_param_handles h;
- float pitch_control_last = 0.0f;
- float roll_control_last = 0.0f;
-
static bool initialized = false;
- float diff_filter_factor = 1.0f;
-
/* initialize the pid controllers when the function is called for the first time */
if (initialized == false) {
parameters_init(&h);
@@ -210,13 +201,11 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
/* control pitch (forward) output */
float pitch_control = pid_calculate(&pitch_rate_controller, rate_sp->pitch ,
- rates[1], 0.0f, deltaT,
- &control_debug->pitch_rate_p, &control_debug->pitch_rate_i, &control_debug->pitch_rate_d);
+ rates[1], 0.0f, deltaT);
/* control roll (left/right) output */
float roll_control = pid_calculate(&roll_rate_controller, rate_sp->roll ,
- rates[0], 0.0f, deltaT,
- &control_debug->roll_rate_p, &control_debug->roll_rate_i, &control_debug->roll_rate_d);
+ rates[0], 0.0f, deltaT);
/* control yaw rate */ //XXX use library here
float yaw_rate_control = p.yawrate_p * (rate_sp->yaw - rates[2]);
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.h b/src/modules/multirotor_att_control/multirotor_rate_control.h
index 695ff3e16..362b5ed86 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.h
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.h
@@ -57,10 +57,8 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_control_debug.h>
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[], struct actuator_controls_s *actuators,
- const orb_advert_t *control_debug_pub, struct vehicle_control_debug_s *control_debug);
+ const float rates[], struct actuator_controls_s *actuators);
#endif /* MULTIROTOR_RATE_CONTROL_H_ */