Skip to content

Commit

Permalink
ardupilot_ros: Remove workarounds, use packages-up-to in instructions
Browse files Browse the repository at this point in the history
* Depends on ArduPilot/ardupilot_gz#28
* Use rosdep to install cartographer

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
  • Loading branch information
Ryanf55 authored and pedro-fuoco committed Sep 4, 2023
1 parent 126ac1a commit ca804c8
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 13 deletions.
48 changes: 35 additions & 13 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,45 +1,67 @@
# ardupilot_ros: ROS 2 use cases with Ardupilot

## Requirements :
## Requirements

### System Requirements

* [ROS Humble](https://docs.ros.org/en/humble/Installation.html)

* [Gazebo Garden](https://gazebosim.org/docs/garden/install)

* [Cartographer ROS](https://google-cartographer-ros.readthedocs.io/en/latest/)
* Recommended: Install Google Cartographer with rosdep

### Workspace Requirements

* [ardupilot_gz](https://github.com/ArduPilot/ardupilot_gz)
* Here are two workarounds for know issues in the installation of `ardupilot_gz` (they should be fixed soon)
* [Handle microxrceddsgen dependency](https://github.com/ArduPilot/ardupilot_gz/issues/19)
* Set the ENABLE_DDS ardupilot parameter manually if it isn't set

* [cartographer_ros]()

## Installation

Clone this repository into your ros2 workspace alongside ardupilot_gz
Clone this repository into your ros2 workspace alongside ardupilot_gz:
```bash
cd ~/ros2_ws/src
git clone git@github.com:ardupilot/ardupilot_ros.git -b humble
git clone git@github.com:ardupilot/ardupilot_ros.git
```
Build it with colcon build

Install dependencies using rosdep:
```bash
cd ~/ros2_ws
source install/setup.sh
colcon build --packages-select ardupilot_ros
rosdep install --from-paths src --ignore-src -r
```

## Build

Build it with colcon build:
```bash
cd ~/ros2_ws
source /opt/ros/humble/setup.bash
colcon build --packages-up-to ardupilot_ros ardupilot_gz_bringup

```

## Usage

### 1. Cartographer running with lidar on copter
### 1. Cartographer running with LiDAR on copter

This simulation has an iris copter equipped with a 360 degrees 2D lidar in a maze world, to launch it run:
This simulation has an Iris copter equipped with a 360 degrees 2D LiDAR in a maze world.
To launch rviz and gazebo, run:

```bash
cd ~/ros2_ws
source install/setup.sh
ros2 launch ardupilot_gz_bringup iris_maze.launch.py
```
With the world and copter in place, launch cartographer to generate SLAM:
In another terminal, with the world and copter in place, launch cartographer to generate SLAM:

```bash
cd ~/ros2_ws
source install/setup.sh
ros2 launch ardupilot_ros cartographer.launch.py
```

If you'd like to get the information from Cartographer to go into Ardupilot's extended kalman filter, you will need to change some parameters, you can do that through any GCS, including mavproxy:
If you'd like to get the information from Cartographer to go into Ardupilot's extended kalman filter, you will need to change some parameters. You can do that through any GCS, including mavproxy:

- AHRS_EKF_TYPE = 3 to use EKF3
- EK2_ENABLE = 0 to disable EKF2
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<description>The ardupilot ROS 2 use cases package</description>
<maintainer email="pedrofuoco6@gmail.com">Pedro Fuoco</maintainer>
<license>GPLv3+</license>
<exec_depend>cartographer_ros</exec_depend>
<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
Expand Down

0 comments on commit ca804c8

Please sign in to comment.