Skip to content

Commit

Permalink
Restructured ardupilot_ros
Browse files Browse the repository at this point in the history
  • Loading branch information
snktshrma committed Jan 19, 2025
1 parent 5c7086e commit f8fe6b9
Show file tree
Hide file tree
Showing 17 changed files with 184 additions and 14 deletions.
12 changes: 6 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

* [ardupilot_gz](https://github.com/ArduPilot/ardupilot_gz)

* [cartographer_ros]()
* [ardupilot_ros]()

## Installation

Expand Down Expand Up @@ -60,7 +60,7 @@ In another terminal, with the world and copter in place, launch cartographer to
```bash
cd ~/ros2_ws
source install/setup.bash
ros2 launch ardupilot_ros cartographer.launch.py
ros2 launch ardupilot_cartographer 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:
Expand All @@ -87,12 +87,12 @@ The joystick controller allows you to control ArduPilot through a ROS joy topic.
```bash
cd ~/ros2_ws
source install/setup.bash
ros2 run ardupilot_ros joy_controller
ros2 run ardupilot_cartographer joy_controller
```

Then run the controller using,

`ros2 run ardupilot_ros joy_controller`
`ros2 run ardupilot_cartographer joy_controller`

Now, using the keyboard keys you can control the drone.

Expand All @@ -112,15 +112,15 @@ Launch cartographer:
```bash
cd ~/ros2_ws
source install/setup.sh
ros2 launch ardupilot_ros cartographer.launch.py rviz:=false
ros2 launch ardupilot_cartographer cartographer.launch.py rviz:=false
```

Launch nav2:

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

Takeoff the Copter using `mavproxy` to an altitude of 2.5m:
Expand Down
147 changes: 147 additions & 0 deletions ardupilot_cartographer/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,147 @@
# ardupilot_ros: ROS 2 use cases with Ardupilot

[![pre-commit](https://img.shields.io/badge/pre--commit-enabled-brightgreen?logo=pre-commit)](https://github.com/pre-commit/pre-commit)

## 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)

* [cartographer_ros]()

## Installation

Clone this repository into your ros2 workspace alongside ardupilot_gz:
```bash
cd ~/ros2_ws/src
git clone [email protected]:ardupilot/ardupilot_ros.git
```

Install dependencies using rosdep:
```bash
cd ~/ros2_ws
rosdep install --from-paths src --ignore-src -r --skip-keys gazebo-ros-pkgs
```

## Build

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

```

## Usage

### 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 rviz and gazebo, run:

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

```bash
cd ~/ros2_ws
source install/setup.bash
ros2 launch ardupilot_cartographer 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:

- AHRS_EKF_TYPE = 3 to use EKF3
- EK2_ENABLE = 0 to disable EKF2
- EK3_ENABLE = 1 to enable EKF3
- EK3_SRC1_POSXY = 6 to set position horizontal source to ExternalNAV
- EK3_SRC1_POSZ = 1 to set position vertical source to Baro
- EK3_SRC1_VELXY = 6 to set velocity horizontal source to ExternalNAV
- EK3_SRC1_VELZ = 6 to set vertical velocity source to ExternalNAV
- EK3_SRC1_YAW = 6 to set yaw source to ExternalNAV
- VISO_TYPE = 1 to enable visual odometry
- ARMING_CHECK = 388598 (optional, to disable GPS checks)

The parameters above are recommended for SITL. If you plan on using this on a real copter, it is a good idea to setup a second source of EKF. This way the robot doesn't crash if the external odometry you are providing stops publishing or gets lost.

Please refer to this link for more information on [Common EKF Sources](https://ardupilot.org/copter/docs/common-ekf-sources.html>) as well as this guide on [GPS / Non-GPS Transitions](https://ardupilot.org/copter/docs/common-non-gps-to-gps.html).

### 2. Joystick Controller

The joystick controller allows you to control ArduPilot through a ROS joy topic.

```bash
cd ~/ros2_ws
source install/setup.bash
ros2 run ardupilot_cartographer joy_controller
```

Then run the controller using,

`ros2 run ardupilot_cartographer joy_controller`

Now, using the keyboard keys you can control the drone.

### 3. Obstacle avoidance using Cartographer and Nav2

Using the same simulation as before, the nav2 node can be launched to control the copter once it is in the air.

Launch the simulation:

```bash
cd ~/ros2_ws
source install/setup.sh
ros2 launch ardupilot_gz_bringup iris_maze.launch.py rviz:=false
```
Launch cartographer:

```bash
cd ~/ros2_ws
source install/setup.sh
ros2 launch ardupilot_cartographer cartographer.launch.py rviz:=false
```

Launch nav2:

```bash
cd ~/ros2_ws
source install/setup.sh
ros2 launch ardupilot_cartographer navigation.launch.py
```

Takeoff the Copter using `mavproxy` to an altitude of 2.5m:

```bash
mavproxy.py --console --map --aircraft test --master=:14550

mode guided

arm throttle

takeoff 2.5
```

You may now navigate while mapping using the `Nav2 Goal` tool in RVIZ!

## Contribution Guideline

* Ensure the [pre-commit](https://github.com/pre-commit/pre-commit) hooks pass locally before creating your pull request by installing the hooks before committing.
```bash
pre-commit install
git commit
```
* See the [ArduPilot Contributing Guide](https://github.com/ArduPilot/ardupilot/blob/master/.github/CONTRIBUTING.md)
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ def generate_launch_description():
parameters=[{"use_sim_time": LaunchConfiguration("use_sim_time")}],
arguments=[
"-configuration_directory",
FindPackageShare("ardupilot_ros").find("ardupilot_ros") + "/config",
FindPackageShare("ardupilot_cartographer").find("ardupilot_cartographer") + "/config",
"-configuration_basename",
"cartographer.lua",
],
Expand Down Expand Up @@ -64,7 +64,7 @@ def generate_launch_description():
"-d",
str(
Path(
FindPackageShare("ardupilot_ros").find("ardupilot_ros"),
FindPackageShare("ardupilot_cartographer").find("ardupilot_cartographer"),
"rviz",
"cartographer.rviz",
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ def generate_launch_description():
),
launch_arguments={
"use_sim_time": "true",
"params_file": FindPackageShare("ardupilot_ros").find(
"ardupilot_ros"
"params_file": FindPackageShare("ardupilot_cartographer").find(
"ardupilot_cartographer"
)
+ "/config"
+ "/navigation.yaml",
Expand Down Expand Up @@ -76,7 +76,7 @@ def generate_launch_description():
"-d",
str(
Path(
FindPackageShare("ardupilot_ros").find("ardupilot_ros"),
FindPackageShare("ardupilot_cartographer").find("ardupilot_cartographer"),
"rviz",
"navigation.rviz",
)
Expand Down
File renamed without changes.
2 changes: 1 addition & 1 deletion package.xml → ardupilot_cartographer/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ardupilot_ros</name>
<name>ardupilot_cartographer</name>
<version>0.0.0</version>
<description>The ardupilot ROS 2 use cases package</description>
<maintainer email="[email protected]">Pedro Fuoco</maintainer>
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
4 changes: 2 additions & 2 deletions setup.py → ardupilot_cartographer/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
from glob import glob
from setuptools import setup

package_name = "ardupilot_ros"
package_name = "ardupilot_cartographer"

setup(
name=package_name,
Expand Down Expand Up @@ -36,6 +36,6 @@
license="GPLv3+",
tests_require=["pytest"],
entry_points={
"console_scripts": ["joy_controller=ardupilot_ros.joy_controller:main"],
"console_scripts": ["joy_controller=ardupilot_cartographer.joy_controller:main"],
},
)
6 changes: 6 additions & 0 deletions ardupilot_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
cmake_minimum_required(VERSION 3.8)

project(ardupilot_ros)
find_package(ament_cmake REQUIRED)
ament_package()

17 changes: 17 additions & 0 deletions ardupilot_ros/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?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>ardupilot_ros</name>
<version>1.0.0</version>
<description>ardupilot_ros meta-package</description>
<!-- <maintainer email="">Ryan Friedman</maintainer> -->
<maintainer email="[email protected]">Pedro Fuoco</maintainer>
<maintainer email="[email protected]">Sanket Sharma</maintainer>
<license>GPLv3</license>
<exec_depend>ardupilot_cartographer</exec_depend>

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

0 comments on commit f8fe6b9

Please sign in to comment.