Skip to content

Commit

Permalink
Move examples to separate package inside repository.
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 6f182bc commit e6faac0
Show file tree
Hide file tree
Showing 58 changed files with 586 additions and 69 deletions.
21 changes: 2 additions & 19 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,20 +1,3 @@
# PX4-ROS2 bridge
# tbd

[![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 package materializes the ROS2 side of PX4-FastRTPS/DDS bridge, establishing a bridge between the PX4 autopilot stack through a micro-RTPS bridge, Fast-RTPS(DDS) and ROS2. It has a straight dependency on the [`px4_msgs`](https://github.com/PX4/px4_msgs) package, as it depends on the IDL files, to generate the micro-RTPS bridge agent, and on the ROS interfaces and typesupport, to allow building and running the example nodes.

The [`master`](https://github.com/PX4/px4_ros_com/tree/master) branch of this package composes the ROS2 package and the ROS2 side (agent) of the bridge. The [`ros1`](https://github.com/PX4/px4_ros_com/tree/ros1) branch is a product of the `master` and represents the ROS(1) package and the ROS(1) side of the bridge, for wich it is required using the [`ros1_bridge`](https://github.com/ros2/ros1_bridge).

## Install, build and usage

Check the [RTPS/ROS2 Interface](https://dev.px4.io/en/middleware/micrortps.html) section on the PX4 Devguide for details on how to install the required dependencies, build the package (composed by the two branches) and use it.

## 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)
main repo readme
32 changes: 32 additions & 0 deletions examples/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
# 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.

It is assumed that a reads has a basic understanding of running ROS2 applications as well as PX4.

# Layout

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.

The examples are structured:

* `listeners`

...

* `publisher` ...

* `offboard` ...


# Using Examples

...

# Copying Examples

...

# Contributing Examples

...
25 changes: 25 additions & 0 deletions examples/listeners/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.5)
project(px4_ros_com_listener_examples)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
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)

ament_package()

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

listeners readme
23 changes: 23 additions & 0 deletions examples/listeners/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>px4_ros_com_listener_examples</name>
<version>1.0.0</version>
<description>Example of ROS2 and Px4 interaction - listeners</description>
<license>BSD 3-Clause</license>
<maintainer email="[email protected]">Nuno Marques</maintainer>
<author email="[email protected]">Nuno Marques</author>
<author email="[email protected]">Bastian Jäger</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>px4_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
* 2018 PX4 Pro Development Team. All rights reserved.
* 2021 PX4 Pro Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -33,7 +33,7 @@

/**
* @brief Sensor Combined uORB topic listener example
* @file sensor_combined_listener.cpp
* @file 01_sensor_combined_listener.cpp
* @addtogroup examples
* @author Nuno Marques <[email protected]>
* @author Vicente Monge
Expand All @@ -50,10 +50,7 @@ class SensorCombinedListener : public rclcpp::Node
public:
explicit SensorCombinedListener() : Node("sensor_combined_listener") {
subscription_ = this->create_subscription<px4_msgs::msg::SensorCombined>(
"fmu/sensor_combined/out",
#ifdef ROS_DEFAULT_API
10,
#endif
"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;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright 2019 PX4 Development Team. All rights reserved.
* Copyright 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -32,7 +32,7 @@

/**
* @brief Vehicle GPS position uORB topic listener example
* @file vehicle_global_position_listener.cpp
* @file 02_vehicle_global_position_listener.cpp
* @addtogroup examples
* @author Nuno Marques <[email protected]>
*/
Expand All @@ -48,10 +48,7 @@ class VehicleGpsPositionListener : public rclcpp::Node
public:
explicit VehicleGpsPositionListener() : Node("vehicle_global_position_listener") {
subscription_ = this->create_subscription<px4_msgs::msg::VehicleGpsPosition>(
"fmu/vehicle_gps_position/out",
#ifdef ROS_DEFAULT_API
10,
#endif
"fmu/vehicle_gps_position/out", 10,
[this](const px4_msgs::msg::VehicleGpsPosition::UniquePtr msg) {
std::cout << "\n\n\n\n\n\n\n\n\n\n";
std::cout << "RECEIVED VEHICLE GPS POSITION DATA" << std::endl;
Expand Down
21 changes: 21 additions & 0 deletions examples/offboard/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
cmake_minimum_required(VERSION 3.5)
project(px4_ros_com_offboard_example)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(px4_msgs REQUIRED)

add_executable(offboard_control src/offboard_control.cpp)
ament_target_dependencies(offboard_control rclcpp px4_msgs)

ament_package()

install(
TARGETS
offboard_control
DESTINATION
lib/${PROJECT_NAME})
3 changes: 3 additions & 0 deletions examples/offboard/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# tbd

offbaord readme
23 changes: 23 additions & 0 deletions examples/offboard/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>px4_ros_com_offboard_example</name>
<version>1.0.0</version>
<description>Example of ROS2 and Px4 interaction - offboard</description>
<license>BSD 3-Clause</license>
<maintainer email="[email protected]">Nuno Marques</maintainer>
<author email="[email protected]">Nuno Marques</author>
<author email="[email protected]">Bastian Jäger</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>px4_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright 2020 PX4 Development Team. All rights reserved.
* Copyright 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -61,21 +61,12 @@ using namespace px4_msgs::msg;
class OffboardControl : public rclcpp::Node {
public:
OffboardControl() : Node("offboard_control") {
#ifdef ROS_DEFAULT_API
offboard_control_mode_publisher_ =
this->create_publisher<OffboardControlMode>("fmu/offboard_control_mode/in", 10);
trajectory_setpoint_publisher_ =
this->create_publisher<TrajectorySetpoint>("fmu/trajectory_setpoint/in", 10);
vehicle_command_publisher_ =
this->create_publisher<VehicleCommand>("fmu/vehicle_command/in", 10);
#else
offboard_control_mode_publisher_ =
this->create_publisher<OffboardControlMode>("fmu/offboard_control_mode/in");
trajectory_setpoint_publisher_ =
this->create_publisher<TrajectorySetpoint>("fmu/trajectory_setpoint/in");
vehicle_command_publisher_ =
this->create_publisher<VehicleCommand>("fmu/vehicle_command/in");
#endif

// get common timestamp
timesync_sub_ =
Expand All @@ -84,6 +75,15 @@ class OffboardControl : public rclcpp::Node {
timestamp_.store(msg->timestamp);
});


this->declare_parameter("pos_x_m");
this->declare_parameter("pos_y_m");
this->declare_parameter("pos_z_m");

this->get_parameter_or("pos_x_m", pos_x_m_, 0.f);
this->get_parameter_or("pos_y_m", pos_y_m_, 0.f);
this->get_parameter_or("pos_z_m", pos_z_m_, -5.f);

offboard_setpoint_counter_ = 0;

auto timer_callback = [this]() -> void {
Expand All @@ -93,7 +93,7 @@ class OffboardControl : public rclcpp::Node {
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);

// Arm the vehicle
this->arm();
//this->arm();
}

// offboard_control_mode needs to be paired with trajectory_setpoint
Expand Down Expand Up @@ -127,6 +127,10 @@ class OffboardControl : public rclcpp::Node {
void publish_trajectory_setpoint() const;
void publish_vehicle_command(uint16_t command, float param1 = 0.0,
float param2 = 0.0) const;

float pos_x_m_{0.f};
float pos_y_m_{0.f};
float pos_z_m_{0.f};
};

/**
Expand Down Expand Up @@ -172,10 +176,10 @@ void OffboardControl::publish_offboard_control_mode() const {
void OffboardControl::publish_trajectory_setpoint() const {
TrajectorySetpoint msg{};
msg.timestamp = timestamp_.load();
msg.x = 0.0;
msg.y = 0.0;
msg.z = -5.0;
msg.yaw = -3.14; // [-PI:PI]
msg.x = pos_x_m_;
msg.y = pos_y_m_;
msg.z = pos_z_m_;
msg.yaw = NAN; // [-PI:PI]

trajectory_setpoint_publisher_->publish(msg);
}
Expand Down
37 changes: 37 additions & 0 deletions examples/publishers/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
cmake_minimum_required(VERSION 3.5)
project(px4_ros_com_publisher_examples)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(px4_msgs REQUIRED)

add_executable(debug_vect_publisher src/01_debug_vect_publisher.cpp)
ament_target_dependencies(debug_vect_publisher rclcpp px4_msgs)

add_executable(arm_publisher src/02_arm_publisher.cpp)
ament_target_dependencies(arm_publisher rclcpp px4_msgs)

add_executable(disarm_publisher src/03_disarm_publisher.cpp)
ament_target_dependencies(disarm_publisher rclcpp px4_msgs)

add_executable(takeoff_publisher src/04_takeoff_publisher.cpp)
ament_target_dependencies(takeoff_publisher rclcpp px4_msgs)

add_executable(land_publisher src/05_land_publisher.cpp)
ament_target_dependencies(land_publisher rclcpp px4_msgs)

ament_package()

install(
TARGETS
debug_vect_publisher
arm_publisher
disarm_publisher
takeoff_publisher
land_publisher
DESTINATION
lib/${PROJECT_NAME})
3 changes: 3 additions & 0 deletions examples/publishers/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# tbd

publishers readme
23 changes: 23 additions & 0 deletions examples/publishers/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>px4_ros_com_publisher_examples</name>
<version>0.1.0</version>
<description>Example of ROS2 and Px4 interaction - advertisers</description>
<license>BSD 3-Clause</license>
<maintainer email="[email protected]">Nuno Marques</maintainer>
<author email="[email protected]">Nuno Marques</author>
<author email="[email protected]">Bastian Jäger</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>px4_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit e6faac0

Please sign in to comment.