Pprzros

From PaparazziUAV
Revision as of 05:04, 26 July 2017 by Guido (talk | contribs)
Jump to navigation Jump to search

PPRZROS

PPRZROS is a Robot Operating System (ROS) package bridging ROS and Paparazzi, to get the best of both worlds.


Overview

Its role is to convert Paparazzi messages into ROS format and ROS messages into Paparazzi format. More specifically, incoming paparazzi messages are converted into a generic ROS message containing generic information about the message and the binary data associated with the message. Messages coming in ROS format are translated to a generic paparazzi message with the same format: generic information and data in binary form.
To start the PPRZROS node, it requires a connection type (UDP, Serial or Ivy) and a Destination (plus some other optional infos). Once started the PPRZROS node will create two ROS topics:

  • /to_ros : PPRZROS is publishing in this topic. Messages coming from the Destination will be translated into ROS format and published on this topic.
  • /from_ros : PPRZROS is subscribing (listening) to this topic. Any message sent to this topic, by other ROS nodes (programs), will be translated into a Paparazzi message and sent to the Destination.
PPRZROS in a glimpse

Installation

Running PPRZROS

There are two ways to start the PPRZROS node:

  • Directly as an independent ROS node :

First, be sure that the rosmaster is up and running by starting the roscore
$ roscore
And then start the node,
$ rosrun pprzros pprzros_run connexion_type destination [OPTIONS]
the OPTIONS will vary depending on the connexion_type and can be displayed by starting the rosnode with the -h (--help) option.

  • Via a .launch file which allows to start the PPRZROS node along with some other nodes that might be useful for your application,

$  roslaunch pprzros my_script.launch

Example

An example .launch file is provided in the /launch directory of the package. We will go through it to show how a message can be sent to the Paparazzi Destination from ROS.
<?xml version="1.0"?>
<launch>
<node pkg="pprzros" type="pprzros_run" name="pprzros" args="udp -d 192.168.1.1" output="screen"/>
<node pkg="rostopic" type="rostopic" name="send_test_ping" args="pub -r 10 /from_ros pprzros_msgs/PprzrosMsg '{header: auto, version: 1, len: 0, class_name: 'datalink', comp_id: 0, msg_name: 'PING', sender_id: 0, receiver_id: 201, checksum: 0, data: []}'" output="screen"/>
<node pkg="rostopic" type="rostopic" name="echo_test_pong" args="echo -c /to_ros" output="screen"/>
</launch>

In the following, we go through each line to understand its role First starting the PPRZROS node
<node pkg="pprzros" type="pprzros_run" name="pprzros" args="udp -d 192.168.1.1" output="screen"/>
Then, the rostopic package is called to create a node publishing a given message. This message is published on the /from_ros topic and is of type PprzrosMsg. The content of the message is then described in YAML format. We can see here that it is a simple PING message, so there is no content (data == []).
<node pkg="rostopic" type="rostopic" name="send_test_ping" args="pub -r 10 /from_ros pprzros_msgs/PprzrosMsg '{header: auto, version: 1, len: 0, class_name: 'datalink', comp_id: 0, msg_name: 'PING', sender_id: 0, receiver_id: 201, checksum: 0, data: []}'" output="screen"/>
Finally, we create a node, from the rostopic package, to subscribe to the /to_ros topic and listen if any PONG is message is answering our PINGs.
<node pkg="rostopic" type="rostopic" name="echo_test_pong" args="echo -c /to_ros" output="screen"/>
- Under development -