couple of dependency fixes

This commit is contained in:
FranckHumanitas 2017-04-11 13:27:16 +00:00
parent 4234f895f8
commit 4e6a2a7d43
3 changed files with 6 additions and 2 deletions

View File

@ -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
)

View File

@ -13,6 +13,9 @@
<build_depend>std_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<build_depend>mavros_msgs</build_depend>
<run_depend>mavros_msgs</run_depend>
<export>
</export>

View File

@ -8,7 +8,7 @@
#include <stdlib.h>
#include <time.h>
#include<mavros_msgs/Mavlink.h>
#include <mavros_msgs/Mavlink.h>
#include <ros/ros.h>