Skip to content

ROS interface with PX4 micrortps ( FastRTPS/DDS ). Bridge between PX4 micrortps and your client ROS appliation without ROS2.

License

Notifications You must be signed in to change notification settings

Ravinspect/px4_micrortps_ros

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

10 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

This code repository was created for ROS Melodic and RTPS communication instead of Mavlink.

MicroRTPS operates in 3 layers.

  • micrortps_client runs on px4 microcontroller or ardunio microcontroller.
  • micrortps_agent runs on the host computer and exchanges data with the client. (we have ubuntu computer defined on jatson xaiver)
  • The px4_micrortps_ros package is a mix of classes and ROS nodes generated by FastRTPS-Gen. Exchanges data with micrortps_agent.

For detail setup and instruction: https://docs.px4.io/master/en/dev_setup/fast-dds-installation.html


Tested on our enviroment and hardware.

Environment

  • Ubuntu 18.04
  • ROS Melodic
  • PX4 V1.12.3
  • FastDDS v 2.0.2
  • FastRTPS-Gen 1.0.4
  • foonathan_memory_vendor
  • Java
  • Gradle 6.4.1

Hardware

  • FMUv5

  • Jetson Xavier / Ubuntu Linux

  • Telem to USB converter

Setup

JAVA Install: ( for Gradle)

    sudo apt update
    java -version
    sudo apt install default-jre

Gradle Kurulum:

Gradle v6.4.1 https://gradle.org/releases/

    $ mkdir /opt/gradle
    $ unzip -d /opt/gradle gradle-6.4.1-bin.zip
    $ ls /opt/gradle/gradle-6.4.1
    LICENSE  NOTICE  bin  getting-started.html  init.d  lib  media

Foonathan memory install:

    git clone -b v1.0.0 https://github.com/eProsima/foonathan_memory_vendor.git
    cd foonathan_memory_vendor
    mkdir build && cd build
    cmake ..
    sudo cmake --build . --target install

Fast DDS

$ git clone --recursive https://github.com/eProsima/Fast-DDS.git -b v2.0.2 ~/FastDDS-2.0.2
$ cd ~/FastDDS-2.0.2
$ mkdir build && cd build
$ cmake -DTHIRDPARTY=ON -DSECURITY=ON ..
$ make -j$(nproc --all)
$ sudo make install

Fast-RTPS-Gen

git clone --recursive https://github.com/eProsima/Fast-DDS-Gen.git -b v1.0.4 ~/Fast-RTPS-Gen \
    && cd ~/Fast-RTPS-Gen \
    && gradle assemble \
    && sudo env "PATH=$PATH" gradle install

PX4 AutoPilot Firmware Download:

  • From https://github.com/PX4/PX4-Autopilot, the stable version or the version we want to work on is selected. (We chose our experiments as v12.1.3.)

  • The following command is run to compile the firmware that we will use on the px4 mini hardware.

  • /home/{username}/PX4-Autopilot/ $ make px4_fmu_v5_rtps

    output is given below.

    /home/ravinspect/PX4-Autopilot/build/px4_fmu-v5_rtps

  • The px4_fmu-v5_rtps.px4 file in this output is uploaded to the PX4 Mini (installed on the SD card). We use QGroundControl for this.

  • After installing it is necessary to update the firmware parameters via QgroundControl. For this, we import the parameters we previously exported to the firmware of the device we will use with the help of QGroundControl.

NOT: micrortps_client'ın firmware açılırken aktif olması için

If micrortps_client does not work at startup, we need to manually update the firmware with microssd for now.

  • The etc folder is defined in the firmware.
  • A file called extras.txt is created in the etc folder.
  • Add the following lines to the file.
  • you can find this folder inside the px4_micrortps_ros package.
    set +e

    # For UART communication over the IR/TELM2 port:
    micrortps_client start -d /dev/ttyS1 -b 460800 -t UART

    set -e

NOTE: Here, the opening parameters such as "-b", "-d" may vary depending on the connection type or port.


NOTE: If there are UORB topics (messages) that we deem unnecessary or that we do not want to listen to, in the exchange with micrortps_agent, micrortps_client,

We can clear the recieve or send status before running make px4_fmu_v5_rtps and updating the firmware.


NOTE: In the all_nodelet.launch file in the px4_micrortps_ros package, we can run the nodelets that process the uorb messages we want to listen to or send data to by commenting or removing the comments.


NOTE: Examples of the use of client, agent and intermediate program part (whatever you call the connector bridge) are available in the link below. https://docs.px4.io/master/en/middleware/micrortps.html



Running FASTRTPS

  1. Make sure micrortps_client is running on the firmware. Check the QGroundConsole by typing micrortps_client status in the console. If the autostart we have added to the etc folder does not work, try to change your settings. -b (baudrate) or you can change the telementry port it is connected to (some pixhawks have telem2, telem3 etc. ports and they can also correspond to /dev/ttyS2, /dev/ttyS3).

  2. We go to the file path and compile the agent then install it (No need to repeat this step every time).

This process is in the px4_micrortps_ros package;

  • roslaunch px4_micrortps_ros micrortps_agent_build_test.launch or
  • roslaunch px4_micrortps_ros micrortps_agent_build_prod.launch

micrortps_agent is compiled and prepared to work by running it.

Note: There are important problems here;

  1. Agent may end up running with various errors.
  2. We cannot connect to Mavros.
--- MicroRTPS Agent ---
[   micrortps_agent   ]	Starting link...
[   micrortps_agent   ]	UART transport: device: /dev/ttyUSB0; baudrate: 460800; sleep: 1us; poll: 1ms; flow_control: No
---   Subscribers   ---
- debug_array subscriber started
- debug_key_value subscriber started
- debug_value subscriber started
- debug_vect subscriber started
- offboard_control_mode subscriber started
- optical_flow subscriber started
- position_setpoint subscriber started
- position_setpoint_triplet subscriber started
- telemetry_status subscriber started
- timesync subscriber started
- vehicle_command subscriber started
- vehicle_local_position_setpoint subscriber started
- vehicle_trajectory_waypoint subscriber started
- onboard_computer_status subscriber started
- trajectory_bezier subscriber started
- vehicle_trajectory_bezier subscriber started
- vehicle_mocap_odometry subscriber started
- vehicle_visual_odometry subscriber started
- trajectory_setpoint subscriber started
-----------------------

----   Publishers  ----
- input_rc publisher started
- satellite_info publisher started
- sensor_combined publisher started
- timesync publisher started
- trajectory_waypoint publisher started
- vehicle_attitude publisher started
[   micrortps_agent   ]	vehicle_visual_odometry subscriber matched
- vehicle_control_mode publisher started
- vehicle_local_position publisher started
- vehicle_odometry publisher started
- vehicle_status publisher started
- collision_constraints publisher started
- vehicle_angular_velocity publisher started
- vehicle_trajectory_waypoint_desired publisher started
-----------------------

NOTE: Publishers and subs working with micrortps_agent

Getting started

Running

  1. build the micrortps_agent;
  • build micrortps_agent test env: roslaunch px4_micrortps_ros micrortps_agent_build_test.launch

  • build micrortps_agent prod env: roslaunch px4_micrortps_ros micrortps_agent_build_prod.launch

  1. Launch your px4_sitl_rtps or connect your controller ( Pixhawk etc) via Telem.

  2. Start the micrortps_Agent and all nodes roslaunch px4_micrortps_ros px4_sitl_rtps.launch

References

  1. https://github.com/PX4/PX4-Autopilot
  2. https://docs.px4.io/v1.12/en/middleware/micrortps.html
  3. https://github.com/PX4/px4_ros_com
  4. https://github.com/mavlink/mavros/tree/master
  5. https://mavlink.io/en/messages/common.html
  6. https://discuss.px4.io/ (MAVROS/RTPS/ROS2 Category)

About

ROS interface with PX4 micrortps ( FastRTPS/DDS ). Bridge between PX4 micrortps and your client ROS appliation without ROS2.

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages