Skip to content

Commit

Permalink
Merge branch 'master' into coverity_scan
Browse files Browse the repository at this point in the history
* master: (56 commits)
  fix coverity, #101
  Add package index readme, Fix #101
  move exras to subdirectory, #101
  move mavros to subdirectory, #101
  save changes before moving, #101
  plugins: setpoint: Update setpoint message name.
  plugin: setpoint_attitude: Update message name.
  Add link to ros-*-mavlink package wiki page.
  plugin: gps: Fix gcc 4.6 build (atomic).
  plugin: sys_status: Implement PX4 mode decoding.
  plugin: gps: Add EPH & EPV to diagnostic.
  plugin: gps: Move message processing to individual handlers.
  plugin: rc_io: Replace override service with topic. (ROS API change).
  Add dialect selection notes
  plugins: Change severity for param & wp done messages.
  plugins: Store raw autopilot & mav type values.
  plugins: init ctor (coverity)
  plugin: imu_pub: Add ATTITUDE_QUATERNION support.
  scriptis: mavcmd: Spelling
  scripits: Add mavcmd tool
  ...

Conflicts:
	mavros/CHANGELOG.rst

Update coverity branch for #101.
  • Loading branch information
vooon committed Aug 11, 2014
2 parents 4277946 + 7a40047 commit daf8c6e
Show file tree
Hide file tree
Showing 92 changed files with 2,189 additions and 659 deletions.
6 changes: 4 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
# thanks to jsk-ros-pkg
language: cpp
compiler: gcc
compiler:
- gcc
# - clang
env:
global:
# The next declaration is the encrypted COVERITY_SCAN_TOKEN, created
Expand Down Expand Up @@ -56,6 +58,6 @@ addons:
name: "vooon/mavros"
description: "Build submitted via Travis CI"
notification_email: vooon341@gmail.com
build_command_prepend: "cd ~/ros/ws_$REPOSITORY_NAME/src/mavros && cmake ."
build_command_prepend: "cd ~/ros/ws_$REPOSITORY_NAME/src/mavros/mavros && cmake ."
build_command: "make -j4"
branch_pattern: coverity_scan
145 changes: 9 additions & 136 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,149 +1,22 @@
MAVROS
======

MAVLink extendable communication node for ROS
with proxy for Ground Control Station (e.g. [QGroundControl][1]).
MAVLink extendable communication node for ROS.

ROS API documentation moved to [wiki.ros.org][9].
Since 2014-08-11 this repository contains several packages.


Feutures
--------

- Communication with autopilot via serial port, UDP or TCP (e.g. [ArduPilot][2])
- Internal proxy for Ground Control Station (serial, UDP, TCP)
- [mavlink\_ros][3] compatible ROS topics (Mavlink.msg)
- Plugin system for ROS-MAVLink translation
- Parameter manipulation tool
- Waypoint manipulation tool


Limitations
-----------

Only for linux. Depends on [Boost library][4] >= 1.46 (hydro on 12.04).
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).


Connection URL
mavros package
--------------

*New in 0.7.0*. Connection now defined by URL,
you can use any supported type for FCU and GCS.

Supported schemas:

- Serial: `/path/to/serial/device[:baudrate]`
- Serial: `serial:///path/to/serial/device[:baudrate][?ids=sysid,compid]`
- UDP: `udp://[bind_host[:port]]@[remote_host[:port]][/?ids=sysid,compid]`
- TCP client: `tcp://[server_host][:port][/?ids=sysid,compid]`
- TCP server: `tcp-l://[bind_port][:port][/?ids=sysid,compid]`

Note: ids from URL overrides ids given by parameters.


Programs
--------

### mavros\_node -- main communication node

Main node. Allow disable GCS proxy by setting empty URL.

Run example:

rosrun mavros mavros_node _fcu_url:=/dev/ttyACM0:115200 _gcs_url:=tcp-l://


### gcs\_bridge -- additional UDP proxy

Allows you to add a channel for GCS.
For example if you need to connect one GCS for HIL and the second on the tablet.

Previous name: `ros_udp`.

Example (HIL & DroidPlanner):

rosrun mavros mavros_node _gcs_url:='udp://:14556@hil-host:14551' &
rosrun mavros gcs_bridge _gcs_url:='udp://@nexus7'


### mavparam -- parameter manipulation

Just see `--help`.

Examples:

rosrun mavros mavparam dump /tmp/apm.param
rosrun mavros mavparam load /tmp/apm2.param


### mavwp -- mission manipulation

See `--help`.

Examples:

rosrun mavros mavwp show -p
rosrun mavros dump /tmp/mission.txt


### mavsafety -- safety tool

See `--help`.

Examples:

rosrun mavros mavsafety arm
rosrun mavros mavsafety disarm


Installation
------------

Use `wstool` utility for installation. In your workspace do:

wstool set -t src mavros --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 build 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_generator 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 can add `sudo -s` to last command.
Or you could build debian package by pulling right bloom branch from [mavlink-gbp-release][7]
(common naming: `debian/<rosdistro>/<osdistro>/<package>`) using `dh binary`.
It is main package, please see their [README][mrrm].


Links
-----
mavros\_extras package
----------------------

- [MAVLink][5] -- communication protocol
- [mavlink\_ros][3] -- original ROS node (few messages, no proxy)
- [ArduPilot][2] -- tested autopilot APM:Plane (default command set)
- [QGroundControl][1] -- tested ground control station for linux
- [DroidPlanner][6] -- tested GCS for Android
This package contain some extra nodes and plugins for mavros, please see their [README][exrm].


[1]: http://qgroundcontrol.org/
[2]: http://ardupilot.com/
[3]: https://github.com/mavlink/mavlink_ros
[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
[mrrm]: https://github.com/vooon/mavros/blob/master/mavros/README.md
[exrm]: https://github.com/vooon/mavros/blob/master/mavros_extras/README.md
4 changes: 0 additions & 4 deletions TODO.md

This file was deleted.

3 changes: 0 additions & 3 deletions launch/px4_blacklist.yaml

This file was deleted.

24 changes: 24 additions & 0 deletions CHANGELOG.rst → mavros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,30 @@ Changelog for package mavros

Forthcoming
-----------
* Merge branch 'master' of github.com:vooon/mavros
* 'master' of github.com:vooon/mavros:
Add link to ros-*-mavlink package wiki page.
* plugins: setpoint: Update setpoint message name.
Issue `#94 <https://github.com/vooon/mavros/issues/94>`_, Fix `#97 <https://github.com/vooon/mavros/issues/97>`_.
* plugin: setpoint_attitude: Update message name.
Issues `#94 <https://github.com/vooon/mavros/issues/94>`_, `#97 <https://github.com/vooon/mavros/issues/97>`_.
* Add link to ros-*-mavlink package wiki page.
* plugin: gps: Fix gcc 4.6 build (atomic).
Not recommended to use std::atomic with gcc 4.6.
So i limited to prederined atomics for simple types like int, float etc.
* plugin: sys_status: Implement PX4 mode decoding.
Fix `#84 <https://github.com/vooon/mavros/issues/84>`_.
* plugin: gps: Add EPH & EPV to diagnostic.
Issue `#95 <https://github.com/vooon/mavros/issues/95>`_
* plugin: gps: Move message processing to individual handlers.
Issue `#95 <https://github.com/vooon/mavros/issues/95>`_.
* plugin: rc_io: Replace override service with topic. (ROS API change).
Fix `#93 <https://github.com/vooon/mavros/issues/93>`_.
* Add dialect selection notes
* plugins: Change severity for param & wp done messages.
* plugins: Store raw autopilot & mav type values.
This may fix or not issue `#89 <https://github.com/vooon/mavros/issues/89>`_.
* plugins: init ctor (coverity)
* plugin: imu_pub: Add ATTITUDE_QUATERNION support.
Also reduce copy-paste and use mode readable bitmask check.
Fix `#85 <https://github.com/vooon/mavros/issues/85>`_.
Expand Down
7 changes: 5 additions & 2 deletions CMakeLists.txt → mavros/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)
find_package(Boost REQUIRED COMPONENTS system)
find_package(mavlink REQUIRED)

## Uncomment this if the package has a setup.py. This macro ensures
Expand Down Expand Up @@ -62,6 +62,7 @@ add_message_files(
RCIn.msg
RCOut.msg
RadioStatus.msg
OverrideRCIn.msg
)

## Generate services in the 'srv' folder
Expand All @@ -76,11 +77,11 @@ add_service_files(
WaypointPull.srv
WaypointPush.srv
WaypointGOTO.srv
OverrideRCIn.srv
CommandLong.srv
CommandBool.srv
CommandMode.srv
CommandHome.srv
CommandTOL.srv
StreamRate.srv
)

Expand Down Expand Up @@ -192,6 +193,7 @@ add_library(mavros_plugins
src/plugins/setpoint_velocity.cpp
src/plugins/setpoint_accel.cpp
src/plugins/setpoint_attitude.cpp
src/plugins/vision_speed.cpp
)
add_dependencies(mavros_plugins
mavros_generate_messages_cpp
Expand Down Expand Up @@ -244,6 +246,7 @@ install(PROGRAMS
scripts/mavparam
scripts/mavwp
scripts/mavsafety
scripts/mavcmd
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Expand Down
Loading

0 comments on commit daf8c6e

Please sign in to comment.