Do not fall, Please.
- Table of Contents
- 🚀 Overview
- 🔧 Features
- 📂 Project Structure
- 🛠 Getting Started
- 🔍 Node and Code Descriptions
- 🗺 Project Roadmap
- 🤝 Contributing
offb_control_mavros.git is aimed at simplifying the setup and control of MAVROS for offboard control systems. This repository streamlines integration with ROS nodes and MAVLink protocols, enabling robust and secure UAV operations.
| Feature | Summary |
|---|---|
| ⚙️ Architecture | Leverages C++ and CMake for building a modular offboard control system integrated with ROS2 and MAVROS. |
| 🔌 Integrations | Seamless integration with MAVROS, ROS, and dependencies like ament_cmake, rclcpp,geometry_msgs, nav_msgs, mavros_msgs,tf2_geometry_msgs,and tf2 . |
| 🧩 Modularity | Modular components for position control, mission handling, and waypoint generation, enabling reusability and scalability. |
| 📦 Dependencies | Relies on critical libraries and tools like Eigen3, yaml-cpp. |
└── offb_control_mavros.git/
├── CMakeLists.txt
├── README.md
├── config
│ └── position_controller_config.yaml
├── include
│ └── odometry_processor.hpp
├── package.xml
├── src
│ ├── odometry_processor.cpp
│ ├── offb_keyboard.cpp
│ ├── offb_mission.cpp
│ ├── offb_node.cpp
│ ├── pid_tuning_controller_node.cpp
│ ├── position_controller_node.cpp
│ └── waypoint_creator.cpp
└── tools
├── plot_log.ipynb
└── plot_log_pid_tuning.ipynb
Ensure you have the following tools installed:
- Programming Language: C++17
- Package Manager: CMake(>=3.5)
- ROS 2 with MAVROS plugin
- PX4 Autopilot (for simulation)
Build it using colcon:
# Build
colcon build --packages-select offb_control_mavros
source install/setup.bashRun the project using the compiled executable or specific nodes:
ros2 run offb_control_mavros offb_node
Replace offb_node with any of the following to run the corresponding nodes:
- offb_keyboard_node
- position_controller_node
- pid_tuning_controller_node
- waypoint_creator
- offb_mission
- odometry_processor
Run with SLAM, launch v-SLAM with localization mode:
# cd PX4-Autopilot
make px4_sitl gz_x500_vision
# cd ros2_ws/launch
ros2 launch sim_localization.launch.py map_db_in:=../data/map/gazebo480-20231017-1926.msg
gazebo480-20231017-1926.msg is the map database generated by v-SLAM for 504 test environment.
- position controller node, offb_node, and offb_mission
# launch mavros for simulation
ros2 launch mavros px4.launch fcu_url:="udp://:14540@127.0.0.1:14557"
# run position controller node (after V-SLAM)
ros2 run offb_control_mavros position_controller_node --ros-args --params-file ./data/position_controlle
# run offb_node to control mode
ros2 run offb_control_mavros offb_node
# arm the drone and run the mission, waypoint will start to publish
ros2 run offb_control_mavros offb_mission --ros-args -p source_mode:=vision -p guidance_mode:=global
# run offb_keyboard_node to control the drone as backup
[option] ros2 run offb_control_mavros offb_keyboard_node
- To be updated
Handles UAV state and mission execution. Allows commands like o=offboard, p=position, a=arm, d=disarm, and l=land.
Implements PID-based position control. Configurable via YAML:
position_controller:
ros__parameters:
Kp: 1.0
Ki: 0.0
Kd: 0.0
logging_enabled: true
source_mode: "vision"Manages waypoints and mission states. YAML file example:
tolerance: 0.5
waypoints:
- x: 0
y: 0
z: 1Creates and saves waypoints based on pose data. Supports recording odometry or pose-stamped topics.
Facilitates real-time PID tuning with tools like rqt_reconfigure.
- Implement basic PID controller.
- Add support for advanced control algorithms (e.g., SE3).
- Improve waypoint interpolation.
- Fork the repository.
- Create a feature branch:
git checkout -b feature-name. - Commit your changes:
git commit -m "Feature description". - Push to your fork:
git push origin feature-name. - Open a pull request.