aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mc_att_control
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-08 10:37:01 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-08 10:37:01 +0100
commit87df7c3243412d4fc7a0c40967b2abe078f7a0b2 (patch)
tree63e442c07a3e709ab76f456f366f437c0552d700 /src/modules/mc_att_control
parent65629d09d5e2424c6fcaf261c95f6d6995c4afd7 (diff)
downloadpx4-firmware-87df7c3243412d4fc7a0c40967b2abe078f7a0b2.tar.gz
px4-firmware-87df7c3243412d4fc7a0c40967b2abe078f7a0b2.tar.bz2
px4-firmware-87df7c3243412d4fc7a0c40967b2abe078f7a0b2.zip
move vehicle_attitude_setpoint to msg format
Diffstat (limited to 'src/modules/mc_att_control')
-rw-r--r--src/modules/mc_att_control/mc_att_control_base.cpp4
-rw-r--r--src/modules/mc_att_control/mc_att_control_base.h7
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp6
3 files changed, 6 insertions, 11 deletions
diff --git a/src/modules/mc_att_control/mc_att_control_base.cpp b/src/modules/mc_att_control/mc_att_control_base.cpp
index 5e65e6508..f6b3268b5 100644
--- a/src/modules/mc_att_control/mc_att_control_base.cpp
+++ b/src/modules/mc_att_control/mc_att_control_base.cpp
@@ -172,7 +172,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
if (_v_att_sp.R_valid) {
/* rotation matrix in _att_sp is valid, use it */
- R_sp.set(&_v_att_sp.R_body[0][0]);
+ R_sp.set(&_v_att_sp.R_body[0]);
} else {
/* rotation matrix in _att_sp is not valid, use euler angles instead */
@@ -180,7 +180,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
_v_att_sp.yaw_body);
/* copy rotation matrix back to setpoint struct */
- memcpy(&_v_att_sp.R_body[0][0], &R_sp.data[0][0],
+ memcpy(&_v_att_sp.R_body[0], &R_sp.data[0][0],
sizeof(_v_att_sp.R_body));
_v_att_sp.R_valid = true;
}
diff --git a/src/modules/mc_att_control/mc_att_control_base.h b/src/modules/mc_att_control/mc_att_control_base.h
index 1c2f3fb6f..c1ea52f63 100644
--- a/src/modules/mc_att_control/mc_att_control_base.h
+++ b/src/modules/mc_att_control/mc_att_control_base.h
@@ -34,7 +34,7 @@
/**
* @file mc_att_control_base.h
- *
+ *
* MC Attitude Controller
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
@@ -45,23 +45,20 @@
* @author Roman Bapst <bapstr@ethz.ch>
*
*/
-
+#include <px4.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <math.h>
-#include <drivers/drv_hrt.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/actuator_armed.h>
-#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <lib/mathlib/mathlib.h>
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 887a53508..c0e8957e0 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -52,8 +52,7 @@
* If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers.
*/
-#include <nuttx/config.h>
-#include <stdio.h>
+#include <px4.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
@@ -62,8 +61,6 @@
#include <poll.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
@@ -78,6 +75,7 @@
#include <systemlib/circuit_breaker.h>
#include <lib/mathlib/mathlib.h>
#include <lib/geo/geo.h>
+
#include "mc_att_control_base.h"
/**