diff --git a/CMakeLists.txt b/CMakeLists.txt
index 927d79a..dc508d3 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -11,6 +11,7 @@ set (BOOST_INCLUDEDIR "/usr/include")
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
+ mavros_msgs
)
## System dependencies are found with CMake's conventions
@@ -37,7 +38,7 @@ find_package(catkin REQUIRED COMPONENTS
catkin_package(
INCLUDE_DIRS include
# LIBRARIES xbee_ros_node
- CATKIN_DEPENDS roscpp std_msgs
+ CATKIN_DEPENDS roscpp std_msgs mavros_msgs
# DEPENDS system_lib
)
diff --git a/package.xml b/package.xml
index d009ff0..2d1f3c1 100644
--- a/package.xml
+++ b/package.xml
@@ -13,6 +13,9 @@
std_msgs
roscpp
std_msgs
+
+ mavros_msgs
+ mavros_msgs
diff --git a/src/TestBuzz.cpp b/src/TestBuzz.cpp
index 5341620..3bcffb9 100644
--- a/src/TestBuzz.cpp
+++ b/src/TestBuzz.cpp
@@ -8,7 +8,7 @@
#include
#include
-#include
+#include
#include