msg conflict correction commit
This commit is contained in:
parent
474433def4
commit
a9b1a7598a
|
@ -9,7 +9,6 @@ project(rosbuzz)
|
|||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
std_msgs
|
||||
genmsg
|
||||
mavros_msgs
|
||||
sensor_msgs
|
||||
)
|
||||
|
@ -44,12 +43,12 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
add_message_files(
|
||||
DIRECTORY msg
|
||||
FILES
|
||||
neighbour_pos.msg
|
||||
# add_message_files(
|
||||
# DIRECTORY msg
|
||||
# FILES
|
||||
# neighbour_pos.msg
|
||||
# Message2.msg
|
||||
)
|
||||
# )
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
# add_service_files(
|
||||
|
@ -66,10 +65,10 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
# )
|
||||
|
||||
## Generate added messages and services with any dependencies listed here
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
sensor_msgs
|
||||
)
|
||||
# generate_messages(
|
||||
# DEPENDENCIES
|
||||
# sensor_msgs
|
||||
# )
|
||||
|
||||
################################################
|
||||
## Declare ROS dynamic reconfigure parameters ##
|
||||
|
@ -101,7 +100,7 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS message_runtime
|
||||
#CATKIN_DEPENDS message_runtime
|
||||
# INCLUDE_DIRS include
|
||||
# LIBRARIES buzzros
|
||||
# CATKIN_DEPENDS Buzz roscpp st_msgs
|
||||
|
@ -146,7 +145,7 @@ add_executable(rosbuzz_node src/rosbuzz.cpp
|
|||
src/buzzuav_closures.cpp
|
||||
src/uav_utility.cpp)
|
||||
target_link_libraries(rosbuzz_node ${catkin_LIBRARIES} /usr/local/lib/libbuzz.so /usr/local/lib/libbuzzdbg.so -lpthread)
|
||||
add_dependencies(rosbuzz_node rosbuzz_generate_messages_cpp)
|
||||
#add_dependencies(rosbuzz_node rosbuzz_generate_messages_cpp)
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
|
|
@ -1,2 +0,0 @@
|
|||
Header header
|
||||
sensor_msgs/NavSatFix[] pos_neigh
|
|
@ -14,7 +14,6 @@
|
|||
#include "mavros_msgs/BatteryStatus.h"
|
||||
#include "mavros_msgs/Mavlink.h"
|
||||
#include "sensor_msgs/NavSatStatus.h"
|
||||
#include "rosbuzz/neighbour_pos.h"
|
||||
#include <sstream>
|
||||
#include <buzz/buzzasm.h>
|
||||
#include "buzzuav_closures.h"
|
||||
|
|
Loading…
Reference in New Issue