diff --git a/CMakeLists.txt b/CMakeLists.txt
index 489467db7d..19a14f62af 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -10,7 +10,9 @@ find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
message_generation
+ cmake_modules
)
+find_package(Eigen REQUIRED)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
@@ -48,9 +50,17 @@ find_package(catkin REQUIRED COMPONENTS
## Generate messages in the 'msg' folder
add_message_files(
FILES
- px4_msgs/rc_channels.msg
- px4_msgs/vehicle_attitude.msg
- px4_msgs/rc_channels.msg
+ rc_channels.msg
+ vehicle_attitude.msg
+ vehicle_attitude_setpoint.msg
+ manual_control_setpoint.msg
+ actuator_controls.msg
+ actuator_controls_0.msg
+ vehicle_rates_setpoint.msg
+ vehicle_attitude.msg
+ vehicle_control_mode.msg
+ actuator_armed.msg
+ parameter_update.msg
)
## Generate services in the 'srv' folder
@@ -100,11 +110,19 @@ include_directories(
${catkin_INCLUDE_DIRS}
src/platforms
src/include
+ src/modules
+ src/
+ src/lib
+ ${EIGEN_INCLUDE_DIRS}
)
## Declare a cpp library
add_library(px4
src/platforms/ros/px4_ros_impl.cpp
+ src/platforms/ros/perf_counter.cpp
+ src/platforms/ros/geo.cpp
+ src/lib/mathlib/math/Limits.cpp
+ src/platforms/ros/circuit_breaker.cpp
)
target_link_libraries(px4
@@ -141,14 +159,16 @@ target_link_libraries(subscriber
px4
)
-# add_executable(mc_att_control
- # src/modules/mc_att_control/mc_att_control_main.cpp
- # src/moudles/mc_att_control/mc_att_control_base.cpp)
-# add_dependencies(mc_att_control px4_generate_messages_cpp)
-# target_link_libraries(mc_att_control
- # ${catkin_LIBRARIES}
- # px4
-# )
+## MC Attitude Control
+add_executable(mc_att_control
+ src/modules/mc_att_control/mc_att_control_main.cpp
+ src/modules/mc_att_control/mc_att_control.cpp
+ src/modules/mc_att_control/mc_att_control_base.cpp)
+add_dependencies(mc_att_control px4_generate_messages_cpp)
+target_link_libraries(mc_att_control
+ ${catkin_LIBRARIES}
+ px4
+)
#############
diff --git a/Makefile b/Makefile
index f2e467e5aa..910b785a35 100644
--- a/Makefile
+++ b/Makefile
@@ -224,7 +224,7 @@ updatesubmodules:
$(Q) (git submodule init)
$(Q) (git submodule update)
-MSG_DIR = $(PX4_BASE)msg/px4_msgs
+MSG_DIR = $(PX4_BASE)msg
MSG_TEMPLATE_DIR = $(PX4_BASE)msg/templates
TOPICS_DIR = $(PX4_BASE)src/modules/uORB/topics
TOPICS_TEMPORARY_DIR = $(BUILD_DIR)topics_temporary
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 38c5ebc7b3..edf4fe1a03 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -82,8 +82,8 @@ MODULES += modules/position_estimator_inav
# Vehicle Control
#
#MODULES += modules/segway # XXX Needs GCC 4.7 fix
-MODULES += modules/fw_pos_control_l1
-MODULES += modules/fw_att_control
+#MODULES += modules/fw_pos_control_l1
+#MODULES += modules/fw_att_control
MODULES += modules/mc_att_control
MODULES += modules/mc_pos_control
diff --git a/package.xml b/package.xml
index bc23cdd18f..6662003907 100644
--- a/package.xml
+++ b/package.xml
@@ -43,9 +43,11 @@
roscpp
rospy
std_msgs
+ eigen
roscpp
rospy
std_msgs
+ eigen
diff --git a/src/include/px4.h b/src/include/px4.h
index ca702d63ce..34137ee6f4 100644
--- a/src/include/px4.h
+++ b/src/include/px4.h
@@ -41,6 +41,8 @@
#include "../platforms/px4_includes.h"
#include "../platforms/px4_defines.h"
+#ifdef __cplusplus
#include "../platforms/px4_middleware.h"
#include "../platforms/px4_nodehandle.h"
#include "../platforms/px4_subscriber.h"
+#endif
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 2311e0a7c9..0127796460 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -44,10 +44,7 @@
*/
#pragma once
-
-#include "uORB/topics/fence.h"
-#include "uORB/topics/vehicle_global_position.h"
-
+#include
__BEGIN_DECLS
#include "geo_lookup/geo_mag_declination.h"
diff --git a/src/lib/mathlib/math/Matrix.hpp b/src/lib/mathlib/math/Matrix.hpp
index 806f5933ad..1e76aae603 100644
--- a/src/lib/mathlib/math/Matrix.hpp
+++ b/src/lib/mathlib/math/Matrix.hpp
@@ -49,9 +49,8 @@
#ifdef CONFIG_ARCH_ARM
#include "../CMSIS/Include/arm_math.h"
#else
-#include