Skip to content

Commit

Permalink
Merge github.com:masskro0/px4flow_node_ros2
Browse files Browse the repository at this point in the history
  • Loading branch information
masskro0 committed Feb 13, 2024
2 parents 8653234 + 7b746bc commit 79c0080
Show file tree
Hide file tree
Showing 82 changed files with 179 additions and 14,746 deletions.
31 changes: 26 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,8 +1,29 @@
px-ros-pkg
----------
# px-ros-pkg for ROS2

A repository for PIXHAWK open source code running on ROS.
## Description
Original code from: <a>http://wiki.ros.org/px4flow_node </a><br><br>
A repository for PIXHAWK open source code running on ROS. There was no ROS2 implementation of the px4flow_node and the
official repository seems to be dead. Hence, I ported it to ROS 2.

Notes:
## Supported Platforms
Tested on Ubuntu 22.04 with ROS Humble. Other ROS2 distributions and Ubuntu releases <i>might</i> work.

1. The master branch uses catkin. If you wish to use rosbuild, please use the rosbuild branch.
## Prerequisites:
- Boost library: ```sudo apt install libboost-dev```
- Eigen3: ```sudo apt install libeigen3-dev```
- ROS Humble (or others): <a>https://docs.ros.org/en/humble/Installation.html </a>

## Installation:
Put the whole folder into your ROS workspace and run<br>
```colcon build && . install/setup.bash```<br><br>
Preferably, add this repository as a submodule:<br>
```git submodule add -b main https://github.com/masskro0/px4flow_node_ros2 src/px4flow_node```

## Usage:
First, connect your px4flow sensor and then either launch the mavlink_serial_client:<br>
```ros2 launch mavlink_serial_client mavlink_launch.py```<br><br>
or the px4flow node:<br>
```ros2 launch px4flow px4flow_launch.py```

Both nodes use messages from the <b>px_comm</b> folder. Also, you can modify configuration parameters of both nodes
in <i>drivers/<pkg<pkg>>/config/default.yaml</i>
8 changes: 0 additions & 8 deletions drivers/mavlink_serial_client/.idea/.gitignore

This file was deleted.

2 changes: 0 additions & 2 deletions drivers/mavlink_serial_client/.idea/mavlink_serial_client.iml

This file was deleted.

4 changes: 0 additions & 4 deletions drivers/mavlink_serial_client/.idea/misc.xml

This file was deleted.

8 changes: 0 additions & 8 deletions drivers/mavlink_serial_client/.idea/modules.xml

This file was deleted.

6 changes: 0 additions & 6 deletions drivers/mavlink_serial_client/.idea/vcs.xml

This file was deleted.

30 changes: 13 additions & 17 deletions drivers/mavlink_serial_client/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,57 +18,53 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread system)
find_package(Eigen3 REQUIRED)
find_package(image_transport REQUIRED)
find_package(px_comm REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(px_comm REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread system)
find_package(Eigen3 REQUIRED)

install(
DIRECTORY include/
DESTINATION include
)

###########
## Build ##
###########

include_directories(include
../../mavlink/include/mavlink/v1.0
include
${EIGEN3_INCLUDE_DIRS}
)

add_executable(mavlink_serial_client
add_executable(${PROJECT_NAME}
src/SerialComm.cc
src/mavlink_serial_client.cc
)

ament_target_dependencies(mavlink_serial_client
ament_target_dependencies(${PROJECT_NAME}
rclcpp
std_msgs
sensor_msgs
image_transport
px_comm
sensor_msgs
std_msgs
)

target_link_libraries(mavlink_serial_client
target_link_libraries(${PROJECT_NAME}
Boost::thread
)

install(TARGETS mavlink_serial_client
DESTINATION lib/mavlink_serial_client
install(TARGETS ${PROJECT_NAME}
DESTINATION lib/${PROJECT_NAME}
)

install(
DIRECTORY config/
DESTINATION share/mavlink_serial_client
DESTINATION share/${PROJECT_NAME}
)

install(
DIRECTORY launch/
DESTINATION share/mavlink_serial_client
DESTINATION share/${PROJECT_NAME}
)

ament_package()
ament_package()
Empty file.
Empty file.
Empty file.
Empty file.
Loading

0 comments on commit 79c0080

Please sign in to comment.