Skip to content

Commit

Permalink
Update readme and change from sitl to hitl for mavlink plugin name
Browse files Browse the repository at this point in the history
  • Loading branch information
haitomatic committed Apr 24, 2024
1 parent 58a9c60 commit 67d2e44
Show file tree
Hide file tree
Showing 5 changed files with 32 additions and 144 deletions.
34 changes: 0 additions & 34 deletions .github/workflows/build_test.yml

This file was deleted.

76 changes: 0 additions & 76 deletions .github/workflows/firmware_build_test.yml

This file was deleted.

10 changes: 5 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
project(mavlink_sitl_gazebosim)
project(mavlink_hitl_gazebosim)

list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake")

Expand Down Expand Up @@ -33,9 +33,9 @@ include_directories(
${MAVLINK_INCLUDE_DIRS}
)

add_library(mavlink_sitl_gazebosim SHARED src/gazebo_mavlink_interface.cpp src/mavlink_interface.cpp)
set_property(TARGET mavlink_sitl_gazebosim PROPERTY CXX_STANDARD 17)
target_link_libraries(mavlink_sitl_gazebosim
add_library(mavlink_hitl_gazebosim SHARED src/gazebo_mavlink_interface.cpp src/mavlink_interface.cpp)
set_property(TARGET mavlink_hitl_gazebosim PROPERTY CXX_STANDARD 17)
target_link_libraries(mavlink_hitl_gazebosim
PRIVATE ${Boost_LIBRARIES}
PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
PRIVATE gz-sim${GAZEBO_VERSION}::gz-sim${GAZEBO_VERSION}
Expand All @@ -44,7 +44,7 @@ target_link_libraries(mavlink_sitl_gazebosim

include(GNUInstallDirs)
install(TARGETS
mavlink_sitl_gazebosim
mavlink_hitl_gazebosim
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
)

Expand Down
54 changes: 26 additions & 28 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,37 +1,35 @@
<img align="right" height="20" src="https://auterion.com/wp-content/uploads/2020/05/auterion_logo_default_sunrise.svg">

# Ignition Gazebo for MAVLink SITL and HITL

[![Build Tests](https://github.com/Auterion/sitl_ign_gazebo/actions/workflows/build_test.yml/badge.svg)](https://github.com/Auterion/sitl_ign_gazebo/actions/workflows/build_test.yml)
# Gazebo Sim Plugins
## MAVLink plugin for HITL
A Bridge between Gzsim and Px4 in HITL mode via Mavlink

This is a Software-In-The-Loop/Hardware-In-The-Loop simulation environment for the PX4 autopilot project with [Ignition Gazebo](https://ignitionrobotics.org/home)
### Mavlink subscribed messages (from PX4)
| Type | Description |
|---------------------------------|------------------------------------|
| HIL_ACTUATOR_CONTROLS | Actuator control outputs from PX4 |

## Installation
### Mavlink published messages (to PX4)
| Type | Description |
|----------------------|--------------------------------------------------------------------------------------------------------|
| HIL_SENSOR | The IMU readings in SI units in NED body frame, Magnetic field, absolute and differential pressure|
| HIL_STATE_QUATERNION | Used mainly to send gz model pose info|
| HIL_GPS | The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. Send now mainly to give home GPS coordinate to PX4|

Follow instructions on the [official site](http://gazebosim.org/tutorials?cat=install) to install Gazebo.

```
sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
apt update
apt install ignition-edifice
```
### Gz subscribed topics (from Gzsim)
| Topic name | Type | Description |
|----------------------------------------|------------------|--------------------------------------------|
| /link/base_link/sensor/imu_sensor/imu | gz::msgs::IMU | IMU sensor data |
| /pose/info | gz::msgs::Pose_V | Position and orientation vector of a model |

## Running the simulation
The simulation can be run using the following command at the root of the [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) repository
```
make px4_sitl ignition
```

For more instructions when running the simulation with PX4, follow the [documentation](http://docs.px4.io/master/en/simulation/ignition_gazebo.html)
### Gzsim plugins affected
| Plugin name | Description |
|-----------------------------------------|--------------------------------------------------------------------------|
| gz::sim::systems::MulticopterMotorModel | This system applies a thrust force to models with spinning propellers |



## ABC plugin for HITL/SITL

## Creation and install of debian package on Linux
This creates a debian package and installs the plugins to /usr/lib on Linux. To use this package you must add /usr/lib to IGN_GAZEBO_SYSTEM_PLUGIN_PATH.
```
mkdir build
cd build
cmake ..
make
cpack -G DEB
sudo dpkg -i *.deb
```
2 changes: 1 addition & 1 deletion setup.bash
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# !/bin/bash

export GZ_GAZEBO_SYSTEM_PLUGIN_PATH=/usr/lib
#export GZ_SIM_RESOURCE_PATH=$GZ_GAZEBO_RESOURCE_PATH:$1/Tools/sitl_ign_gazebo/models
#export GZ_SIM_RESOURCE_PATH=$GZ_GAZEBO_RESOURCE_PATH:$1/Tools/hitl_ign_gazebo/models

0 comments on commit 67d2e44

Please sign in to comment.