Skip to content

Commit

Permalink
Update documentation and structure
Browse files Browse the repository at this point in the history
Signed-off-by: Basti <[email protected]>
  • Loading branch information
bastianhjaeger committed Oct 20, 2021
1 parent e6faac0 commit 42308d2
Show file tree
Hide file tree
Showing 19 changed files with 523 additions and 291 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ jobs:
git clone https://github.com/PX4/px4_msgs.git -b master src/px4_msgs
- name: Build package
run: |
cd ~/colcon_ws/src/px4_ros_com/scripts
cd ~/colcon_ws/src/px4_ros_com/px4_ros_com/scripts
./build_ros2_workspace.bash --verbose --no_ros1_bridge --ros_distro ${{ matrix.ros2_distro }} --ros_path /opt/ros/${{ matrix.ros2_distro }}/setup.bash
# - name: Build PX4 Firmware
# run: |
Expand Down
2 changes: 0 additions & 2 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,2 +0,0 @@
src/micrortps_agent/
scripts/__pycache__
File renamed without changes.
25 changes: 23 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,24 @@
# tbd
# PX4-ROS2 bridge

main repo readme
[![GitHub license](https://img.shields.io/github/license/PX4/px4_ros_com.svg)](https://github.com/PX4/px4_ros_com/blob/master/LICENSE) [![GitHub (pre-)release](https://img.shields.io/github/release-pre/PX4/px4_ros_com.svg)](https://github.com/PX4/px4_ros_com/releases/tag/beta) [![DOI](https://zenodo.org/badge/142936318.svg)](https://zenodo.org/badge/latestdoi/142936318) [![Build and Test package](https://github.com/PX4/px4_ros_com/workflows/Build%20and%20Test%20package/badge.svg?branch=master)](https://github.com/PX4/px4_ros_com/actions)

This repository assembles the microRTPS bridge to bridge between PX4 and ROS2 and examples on how to use it. More documentation on the interface can be found [here](https://docs.px4.io/master/en/ros/ros2.html).


## Prerequisites

Check the [RTPS/ROS2 Interface](https://dev.px4.io/en/middleware/micrortps.html) section on the PX4 Devguide and [setup instructions](https://docs.px4.io/master/en/ros/ros2_comm.html#installation-setup)for details on how to install the required dependencies:

- Install [FastDDS](https://docs.px4.io/master/en/ros/ros2_comm.html#install-fast-dds)
- Install [ROS2](https://docs.px4.io/master/en/ros/ros2_comm.html#install-ros-2)


## Bug tracking and feature requests

Use the [Issues](https://github.com/PX4/px4_ros_com/issues) section to create a new issue. Report your issue or feature request [here](https://github.com/PX4/px4_ros_com/issues/new).


## Questions and troubleshooting

Reach the PX4 development team on the `#messaging` or `#ros` PX4 Slack channels:
[![Slack](https://px4-slack.herokuapp.com/badge.svg)](http://slack.px4.io)
56 changes: 41 additions & 15 deletions examples/README.md
Original file line number Diff line number Diff line change
@@ -1,32 +1,58 @@
# Examples

This directory contains a set of examples application for the PX4-ROS2 bridge. All examples are intended to demonstrate basic interactions between PX4 and ROS2. Feel free to play with the code, extend it and copy it into your own project.
This directory contains a set of examples application for the PX4-ROS2 bridge. All examples are intended to demonstrate basic interactions between PX4 and ROS2 by sending or receiving [px4_msgs](https://github.com/PX4/px4_msgs).
Feel free to play with the code, extend it and copy it into your own project.

It is assumed that a reads has a basic understanding of running ROS2 applications as well as PX4.
- We assume that your have a basic understanding of running [ROS2](https://docs.ros.org/) applications as well as [PX4](https://docs.px4.io/master/en/).

# Layout
- Also make sure you have build the [px4_ros_com](../px4_ros_com#install) package successfully.

There are several separate examples. Each example assembles its own executable and can be used standalone to interact with a PX4 vehicle from your ROS2 environment.
## Layout

The examples are structured:
There are several separate examples packages. Each example package assembles its own executables, where each executable can be used in a standalone fashion to interact with a PX4 vehicle from your ROS2 environment.

* `listeners`
The examples are structured (by package and executable):

* [listeners](./listeners): a set of short examples to read data from PX4 in a ROS2 application

- sensor_combined_listener
- vehicle_odometry_listener

* [publishers](./publishers): a set of short examples publishing messages from ROS2 towards PX4

- debug_vect_publisher
- arm_publisher
- disarm_publisher
- takeoff_publisher
- land_publisher

* [offboard](./offboard): a more complex example that arms a robots and sends it to a defined position

...
- offboard_control


## Using Examples

All examples are designed to work with a most possible variety of robots. This can be a multirotor, fixed-wing or VTOL flying robot, a rover or boat. While the examples work on most robots right-away, the are designed to wok in simulation. Maybe you need to adapt the bridge configuration or topic names.

* `publisher` ...
Usually an example needs two things

* `offboard` ...
1. The simulated robot. E.g.:

```
user@ubuntu:~/PX4-Autopilot$ make px4_sitl_rtps gazebo_iris
```

# Using Examples
2. The microRTPS agent:

...
```
user@ubuntu:~/colcon-ws$ micrortps_agent -t UDP
```

# Copying Examples
Detailed instructions and specific limitations will be in the README file for each package or in the section related to a specific binary in the package.

...
Read about more robots and simulated worlds [here](https://docs.px4.io/master/en/simulation/gazebo.html).

# Contributing Examples
## Bug tracking and feature requests

...
Use the [Issues](https://github.com/PX4/px4_ros_com/issues) section to create a new issue. Report your issue or feature request [here](https://github.com/PX4/px4_ros_com/issues/new).
6 changes: 3 additions & 3 deletions examples/listeners/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ find_package(px4_msgs REQUIRED)
add_executable(sensor_combined_listener src/01_sensor_combined_listener.cpp)
ament_target_dependencies(sensor_combined_listener rclcpp px4_msgs)

add_executable(vehicle_gps_position_listener src/02_vehicle_gps_position_listener.cpp)
ament_target_dependencies(vehicle_gps_position_listener rclcpp px4_msgs)
add_executable(vehicle_odometry_listener src/02_vehicle_odometry_listener.cpp)
ament_target_dependencies(vehicle_odometry_listener rclcpp px4_msgs)

ament_package()

install(
TARGETS
sensor_combined_listener
vehicle_gps_position_listener
vehicle_odometry_listener
DESTINATION
lib/${PROJECT_NAME})
92 changes: 90 additions & 2 deletions examples/listeners/README.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,91 @@
# tbd
# Listener Examples

This package contains two executables that subscribe to PX4 robot data and print it to the screen.


For both examples start any robot, e.g.

```
user@ubuntu:~/PX4-Autopilot$ make px4_sitl_rtps gazebo_boat
```

in one terminal and in a new terminal the bridge agent

```
user@ubuntu:~/colcon-ws$ micrortps_agent -t UDP
```

## sensor_combined_listener

The `sensor_combined_listener` binary subscribes to the ROS2 message [SensorCombined](https://github.com/PX4/px4_msgs/blob/master/msg/SensorCombined.msg) under the topic `fmu/sensor_combined/out`. You can find the related uORB message definition on the PX4 repository under [sensor_combined](https://github.com/PX4/PX4-Autopilot/blob/master/msg/sensor_combined.msg).

This message gives you the accelerometer and gyrometer data of your PX4 robot.

Run

```
user@ubuntu:~/colcon-ws$ ros2 run px4_ros_com_listener_examples sensor_combined_listener
```

You should see something like this:

```
user@ubuntu:~/colcon-ws$ ros2 run px4_ros_com_listener_examples sensor_combined_listener
Starting sensor_combined listener node...
RECEIVED SENSOR COMBINED DATA
=============================
ts: 1634661989636389
gyro_rad[0]: 0.00133158
gyro_rad[1]: 0.0015979
gyro_rad[2]: 0.000798948
gyro_integral_dt: 4000
accelerometer_timestamp_relative: 0
accelerometer_m_s2[0]: -0.00957681
accelerometer_m_s2[1]: -0.0814027
accelerometer_m_s2[2]: -9.65941
accelerometer_integral_dt: 4000
```

If you start another terminal, you can see the same data with

```
user@ubuntu:~/colcon-ws$ ros2 topic echo fmu/sensor_combined/out
```


## vehicle_odometry_listener

The `vehicle_odometry_listener` binary subscribes to the ROS2 message [VehicleOdometry](https://github.com/PX4/px4_msgs/blob/master/msg/VehicleOdometry.msg) under the topic `fmu/sensor_combined/out`. You can find the related uORB message definition on the PX4 repository under [vehicle_odometry](https://github.com/PX4/PX4-Autopilot/blob/master/msg/vehicle_odometry.msg).

This message gives you the local position, orientation, velocities and their covariances.

Run

```
user@ubuntu:~/colcon-ws$ ros2 run px4_ros_com_listener_examples vehicle_odometry_listener
```

You should see something like this:

```
user@ubuntu:~/colcon-ws$ ros2 run px4_ros_com_listener_examples vehicle_odometry_listener
Starting vehicle_odometry listener node...
RECEIVED VEHICLE ODOMETRY DATA
==================================
timestamp: 1634662773746560
position: -0.00876204, -0.00276313, -0.0202104
velocity: -0.0124731, -0.0161834, 0.0285649
orientation: 0.709173, -0.00153102, 0.003132, 0.705025
angular vel: 0.00109032, -0.000831208, 0.000450864
```

If you start another terminal, you can see the same data with

```
user@ubuntu:~/colcon-ws$ ros2 ros2 topic echo fmu/vehicle_odometry/out
```

listeners readme
52 changes: 26 additions & 26 deletions examples/listeners/src/01_sensor_combined_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,37 +48,37 @@
class SensorCombinedListener : public rclcpp::Node
{
public:
explicit SensorCombinedListener() : Node("sensor_combined_listener") {
subscription_ = this->create_subscription<px4_msgs::msg::SensorCombined>(
"fmu/sensor_combined/out", 10,
[this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
std::cout << "=============================" << std::endl;
std::cout << "ts: " << msg->timestamp << std::endl;
std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
});
}
explicit SensorCombinedListener() : Node("sensor_combined_listener") {
subscription_ = this->create_subscription<px4_msgs::msg::SensorCombined>(
"fmu/sensor_combined/out", 10,
[this](const px4_msgs::msg::SensorCombined::UniquePtr msg) {
std::cout << "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n";
std::cout << "RECEIVED SENSOR COMBINED DATA" << std::endl;
std::cout << "=============================" << std::endl;
std::cout << "ts: " << msg->timestamp << std::endl;
std::cout << "gyro_rad[0]: " << msg->gyro_rad[0] << std::endl;
std::cout << "gyro_rad[1]: " << msg->gyro_rad[1] << std::endl;
std::cout << "gyro_rad[2]: " << msg->gyro_rad[2] << std::endl;
std::cout << "gyro_integral_dt: " << msg->gyro_integral_dt << std::endl;
std::cout << "accelerometer_timestamp_relative: " << msg->accelerometer_timestamp_relative << std::endl;
std::cout << "accelerometer_m_s2[0]: " << msg->accelerometer_m_s2[0] << std::endl;
std::cout << "accelerometer_m_s2[1]: " << msg->accelerometer_m_s2[1] << std::endl;
std::cout << "accelerometer_m_s2[2]: " << msg->accelerometer_m_s2[2] << std::endl;
std::cout << "accelerometer_integral_dt: " << msg->accelerometer_integral_dt << std::endl;
});
}

private:
rclcpp::Subscription<px4_msgs::msg::SensorCombined>::SharedPtr subscription_;
rclcpp::Subscription<px4_msgs::msg::SensorCombined>::SharedPtr subscription_;
};

int main(int argc, char *argv[])
{
std::cout << "Starting sensor_combined listener node..." << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<SensorCombinedListener>());
std::cout << "Starting sensor_combined listener node..." << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<SensorCombinedListener>());

rclcpp::shutdown();
return 0;
rclcpp::shutdown();
return 0;
}
96 changes: 0 additions & 96 deletions examples/listeners/src/02_vehicle_gps_position_listener.cpp

This file was deleted.

Loading

0 comments on commit 42308d2

Please sign in to comment.