Skip to content

Commit

Permalink
Remove mavlink submodule and move it to package dependency
Browse files Browse the repository at this point in the history
Bloom release tool don't support git submodules,
so i've ceate a package as described in http://wiki.ros.org/bloom/Tutorials/ReleaseThirdParty .

Fix #35.
  • Loading branch information
vooon committed Jun 18, 2014
1 parent 30d14a6 commit 834fa4c
Show file tree
Hide file tree
Showing 6 changed files with 30 additions and 101 deletions.
3 changes: 0 additions & 3 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,3 +0,0 @@
[submodule "mavlink"]
path = mavlink
url = https://github.com/mavlink/mavlink.git
25 changes: 6 additions & 19 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ find_package(catkin REQUIRED COMPONENTS
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
find_package(Boost REQUIRED COMPONENTS system thread date_time)

find_package(mavlink REQUIRED)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
Expand Down Expand Up @@ -97,8 +97,9 @@ generate_messages(
std_msgs
)

## Generate MAVLink headers
include(${CMAKE_CURRENT_SOURCE_DIR}/mavlink.cmake)
## Select MAVLink dialect
#
# TODO: move dialect list to mavlink package

set(MAVLINK_DIALECT "ardupilotmega" CACHE STRING "MAVLink dialect selector")
set_property(CACHE MAVLINK_DIALECT PROPERTY STRINGS
Expand All @@ -114,21 +115,6 @@ set_property(CACHE MAVLINK_DIALECT PROPERTY STRINGS
"sensesoar"
)

set(MAVLINK_DEF
ardupilotmega.xml
autoquad.xml
common.xml
matrixpilot.xml
minimal.xml
pixhawk.xml
slugs.xml
test.xml
ualberta.xml
sensesoar.xml
)

generate_mavlink("1.0" "${MAVLINK_DEF}")


###################################
## catkin specific configuration ##
Expand All @@ -143,7 +129,7 @@ catkin_package(
INCLUDE_DIRS include
LIBRARIES mavconn mavros_plugins
CATKIN_DEPENDS diagnostic_msgs diagnostic_updater pluginlib roscpp sensor_msgs std_msgs tf geometry_msgs
DEPENDS Boost
DEPENDS Boost mavlink
)

###########
Expand All @@ -159,6 +145,7 @@ include_directories(
src/mavconn
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${mavlink_INCLUDE_DIRS}
)

add_definitions(
Expand Down
76 changes: 22 additions & 54 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@ MAVROS
MAVLink extendable communication node for ROS
with UDP proxy for Ground Control Station (e.g. [QGroundControl][1]).

ROS API documentation moved to [wiki.ros.org][9].


Feutures
--------
Expand All @@ -22,61 +24,9 @@ Limitations
Only for linux. Depends on [Boost library][4] >= 1.49.
Catkin build system required (tested with ROS Hydro Medusa and Indigo Igloo).

This package are dependent on ros-\*-mavlink build from [mavlink-gbp-release][7].
Since 2014-06-19 it exists in hydro and indigo package index (so you can install via rosdep).

Parameters
----------

General node parametars:

* ~/serial\_port -- FCU serial device (default: /dev/ttyACM0)
* ~/serial\_baud -- serial baud rate (default: 57600)
* ~/bind\_host -- UDP proxy listen host (default: 0.0.0.0)
* ~/bind\_port -- UDP proxy port (default: 14555)
* ~/gcs\_host -- GCS host
* ~/gcs\_port -- GCS UDP port (default: 14550)
* ~/system\_id -- Node MAVLink System ID (default: 1)
* ~/component\_id -- Node MAVLink Component ID (default: 240 == UDP\_BRIDGE)
* ~/target\_system\_id -- FCU System ID (default: 1)
* ~/target\_component\_id -- FCU Component ID (default: 1)
* ~/startup\_px4\_usb\_quirk -- autostart mavlink via USB on PX4

Plugins parameters:

* ~conn\_timeout -- FCU connection timeout \[sec\] (default: 30.0)
* ~gps/frame\_id -- GPS Header.frame\_id (default: 'gps')
* ~gps/time\_ref\_source -- TimeRefrence Header frame\_id (default: 'gps')
* ~imu/frame\_id -- IMU Header.frame\_id (default: 'fcu')
* ~imu/linear\_acceleration\_stdev -- accel's standard deviation (default: 0.0003)
* ~imu/angular\_velocity\_stdev -- gyro's standard deviation \[rad\] (default: 0.02°)
* ~imu/orientation\_stdev -- deviation for IMU.orientation (default: 1.0)
* ~param/\* -- FCU parameters mapped by ParamPlugin
* ~mission/pull\_after\_gcs -- automatically pull waypoints if GCS pulls (default: off)


Servicies
---------

ParamPlugin:

* ~param/pull -- Pulls FCU params to rosparam
* ~param/push -- Push rosparam to FCU
* ~param/get -- Get one FCU parameter
* ~param/set -- Set one FCU parameter and update rosparam with actual value

WaypointPlugin:

* ~mission/pull -- Pulls FCU waypoints and publish
* ~mission/push -- Push new waypoint list to FCU
* ~mission/clear -- Clear waypoint list
* ~mission/set\_current -- Set current active waypoint (in list)
* ~mission/goto -- send one waypoint (only APM)

CommandPlugin:

* ~cmd/command -- Send any COMMAND\_LONG (all FCU)
* ~cmd/arming -- Arm/Disarm command
* ~cmd/set\_mode -- Set FCU operation mode
* ~cmd/set\_home -- Set home position (if supported)

Programs
--------
Expand Down Expand Up @@ -128,8 +78,23 @@ Use `wstool` utility for installation. In your workspace do:

wstool set -t src --git https://github.com/vooon/mavros.git
wstool update -t src
rosdep install --from-paths src --ignore-src --rosdistro hydro -y

Then use regular `catkin_make` for biuld and install.
Notes: since v0.5 (and [#35][8]) mavlink submodule moved to special ROS 3rd party package [ros-\*-mavlink][7].

### Installing ros-\*-mavlink from source

If rosdep could'not install mavlink library, you could install it from source:

mkdir -p ~/ros_deps/src
cd ~/ros_deps
rosinstall_generate mavlink | tee rosinstall.yaml
wstool init src ./rosinstall.yaml
catkin_make_isolated --install-space $ROSINSTALL --install -DCMAKE_BUILD_TYPE=Release

$ROSINSTALL must be writable for user.
Or you could build debian package by pulling right bloom branch from [mavlink-gbp-release][7].


Testing
Expand All @@ -156,3 +121,6 @@ Links
[4]: http://www.boost.org/
[5]: http://mavlink.org/mavlink/start
[6]: https://github.com/arthurbenemann/droidplanner/
[7]: https://github.com/vooon/mavlink-gbp-release
[8]: https://github.com/vooon/mavros/issues/35
[9]: http://wiki.ros.org/mavros
1 change: 0 additions & 1 deletion mavlink
Submodule mavlink deleted from b3a004
24 changes: 0 additions & 24 deletions mavlink.cmake

This file was deleted.

2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>mavlink</build_depend>
<run_depend>boost</run_depend>
<run_depend>diagnostic_msgs</run_depend>
<run_depend>diagnostic_updater</run_depend>
Expand All @@ -41,6 +42,7 @@
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>mavlink</run_depend>
<test_depend>gtest</test_depend>

<export>
Expand Down

0 comments on commit 834fa4c

Please sign in to comment.