Skip to content
Snippets Groups Projects
Commit 001575e7 authored by Thomas Gubler's avatar Thomas Gubler
Browse files

ros: mavlink node: add mavconn link

parent 2d0c5616
No related branches found
No related tags found
No related merge requests found
......@@ -3,6 +3,7 @@ project(px4)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
add_definitions(-D__PX4_ROS)
add_definitions(-D__EXPORT=)
add_definitions(-DMAVLINK_DIALECT=common)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
......@@ -16,6 +17,7 @@ find_package(catkin REQUIRED COMPONENTS
gazebo_msgs
sensor_msgs
mav_msgs
libmavconn
)
find_package(Eigen REQUIRED)
......@@ -109,7 +111,7 @@ generate_messages(
catkin_package(
INCLUDE_DIRS src/include
LIBRARIES px4
CATKIN_DEPENDS message_runtime roscpp rospy std_msgs
CATKIN_DEPENDS message_runtime roscpp rospy std_msgs libmavconn
DEPENDS system_lib
)
......
......@@ -44,10 +44,12 @@
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>eigen</build_depend>
<build_depend>libmavconn</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>eigen</run_depend>
<run_depend>libmavconn</run_depend>
<!-- The export tag contains other, unspecified, tags -->
......
......@@ -49,6 +49,8 @@ using namespace px4;
Mavlink::Mavlink() :
_n()
{
_link = mavconn::MAVConnInterface::open_url("udp://localhost:14551@localhost:14552");
}
int main(int argc, char **argv)
......
......@@ -41,6 +41,7 @@
*/
#include "ros/ros.h"
#include <mavconn/interface.h>
namespace px4
{
......@@ -55,6 +56,7 @@ public:
protected:
ros::NodeHandle _n;
mavconn::MAVConnInterface::Ptr _link;
};
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment