Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add ardupilot quadcopter command #90

Merged
merged 2 commits into from
Dec 9, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .dockerignore
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

# Include only specific folders/files
!communicators/
!configs/dynamics/

!inno_sim_interface/

Expand Down
40 changes: 22 additions & 18 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,24 @@ UAV HITL Simulator brings up a set of ROS packages, config files and instruction

<img src="https://github.com/ZilantRobotics/innopolis_vtol_dynamics/wiki/assets/welcome/dynamics.png" alt="drawing"/>

The key feature of this simulation is to run it in such a way that the hardware knows nothing about the simulation. This can be done with Cyphal/DroneCAN. It covers more PX4 modules than standard SITL and HITL.
The key feature is to run the simulation on a real hardware and use the actual Cyphal/DroneCAN drivers, so the autopilot knows nothing about the simulation. It covers more PX4 modules than SITL and MAVLink HITL.

**Purpose**

- Simulation of UAV onboard systems at a low hardware level
- Testing and debugging of UAV control systems using a CAN-bus
- Development and testing of intelligent automatic control systems for UAVs
- Testing autopilot peripheral drivers (DroneCAN or Cyphal)
- Testing real hardware components (actuators, payload, power and electrical systems) in pair with control system
- Communication Bus and Wiring Testing
- Fault Injection and Safety Measures
- Environmental and Durability Testing: Vibration Emulation, Long-Duration Endurance Runs
- Training in the development and use of drones, including creating datasets and automated testing

**Minimal requirements (for HITL only):**
**Recommended requirements for HITL:**

- Operating System: Linux based OS such as Ubuntu 22.04
- Raspberry PI 4 is enough
- Operating System: Pure Ubuntu 20.04, 22.04 or 24.04 installation is highly recommended; WSL and VM are not recommended
- Docker: use regular Docker Engine, not Docker Desktop (because Docker Desktop relies on VM)
- Performance: for HITL part even Raspberry PI 4 is enough

**Recommended requirements (for HITL + 3D simulator):**
**Recommended requirements for 3D simulator:**

- Operating System: We've tailored the simulator for modern versions of Windows, Linux, and Mac. Choose the build that matches your OS.
- CPU: Aim for an Intel i7 from the 11th or 12th generation. For those using AMD, any equivalent processor will suffice.
Expand All @@ -29,7 +32,7 @@ The key feature of this simulation is to run it in such a way that the hardware
**Required hardware:**

- Flight controller: fmu-v5, fmu-v6c or fmu-v6x
- CAN-sniffer
- CAN-sniffer: Zubax Babel is recommended, but other CAN-adapters can be suitable as well

## 1. USE CASES

Expand Down Expand Up @@ -308,12 +311,13 @@ Outdated manual instructions:

| Version | ReleaseDate | Major changes |
| ------- | ----------- | ------------- |
| v0.9.0 | Dec .., 2024 | Add px4_fmu-v6c, px4_fmu-v6x, cuav_x7pro, cuav_nora support beside fmu-v5 |
| v0.8.0 | Jun 10, 2024 | Update PX4 from v1.14 to v1.15 |
| v0.7.0 | Oct 31, 2023 | Update PX4 from v1.13 to v1.14 |
| v0.6.0 | Jul 16, 2023 | Add Octorotor dynamics, fault scenarios and Cyphal ESC feedback |
| v0.5.0 | May 17, 2023 | Add Cyphal PX4 v1.13.0 quadcopter, update DroneCAN PX4 from v1.12.1 to v1.13.0 |
| v0.4.0 | May 16, 2022 | Add Cyphal/DroneCAN custom version of Ardupilot |
| v0.3.0 | Aug 25, 2021 | Add Docker |
| v0.2.0 | Aug 17, 2021 | Update to public DroneCAN PX4 v1.12.1 |
| v0.1.0 | Mar 18, 2021 | First public release for private custom version of DroneCAN PX4 v1.11.2, only CUAV V5+, SITL and HITL modes |
| v0.10.0 | In progress... | Add ArduPilot support |
| v0.9.0 | Dec 08, 2024 | Add px4_fmu-v6c, px4_fmu-v6x, cuav_x7pro, cuav_nora support beside fmu-v5 |
| v0.8.0 | Jun 10, 2024 | Update PX4 from v1.14 to v1.15 |
| v0.7.0 | Oct 31, 2023 | Update PX4 from v1.13 to v1.14 |
| v0.6.0 | Jul 16, 2023 | Add Octorotor dynamics, fault scenarios and Cyphal ESC feedback |
| v0.5.0 | May 17, 2023 | Add Cyphal PX4 v1.13.0 quadcopter, update DroneCAN PX4 from v1.12.1 to v1.13.0 |
| v0.4.0 | May 16, 2022 | Add Cyphal/DroneCAN custom version of Ardupilot |
| v0.3.0 | Aug 25, 2021 | Add Docker |
| v0.2.0 | Aug 17, 2021 | Update to public DroneCAN PX4 v1.12.1 |
| v0.1.0 | Mar 18, 2021 | First public release for private custom version of DroneCAN PX4 v1.11.2, only CUAV V5+, SITL and HITL modes |
72 changes: 72 additions & 0 deletions configs/ardupilot_dronecan_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
# Usage: autopilot-configurator --force-calibrate -v --params configs/ardupilot_dronecan_params.yaml
# devid = bus_type * (1 << 0) + bus * (1 << 3) + address * (1 << 8) + devtype * (1 << 8)
# bus_type = devid % 8 = 3
# bus = (devid >> 3) % 32
# address = (devid >> 8) % 256
# devtype = (devid >> 16) % 256

FRAME_CLASS : 1.0 # Quadcopter
CAN_D1_PROTOCOL : 1.0 # DroneCAN
CAN_D1_UC_ESC_BM : 15.0 # For a Quadcopter
CAN_D2_PROTOCOL : 0.0 # Disable
CAN_P1_DRIVER : 1.0 # First driver
CAN_P1_BITRATE : 1000000.0
BRD_SAFETY_DEFLT : 0.0 # Disabled
FS_THR_ENABLE : 0.0 # Disabled
GPS_TYPE : 9.0 # DroneCAN
ATC_RAT_RLL_P : 0.08

# Disable board sensors
EK3_IMU_MASK : 1.0
INS_ENABLE_MASK : 1.0
INS_USE : 1.0 # Enabled
INS_USE2 : 0.0 # Disabled
INS_USE3 : 0.0 # Disabled

# CUAV X7 SPI Compass devid=1114642 bus_type=2 (SPI), bus=2, address=2 devtype=17
# CAN Compass devid=76291 bus_type=3 (CAN), bus=0, address=42 devtype=1
COMPASS_DEV_ID : 76291.0 # DroneCAN magnetometer
COMPASS_PRIO1_ID : 76291.0
COMPASS_USE : 1.0
COMPASS_USE2 : 0.0
COMPASS_USE3 : 0.0
COMPASS_EXTERNAL : 1.0
COMPASS_EXTERN2 : 0.0
COMPASS_EXTERN3 : 0.0
COMPASS_USE : 1.0
COMPASS_USE2 : 0.0
COMPASS_USE3 : 0.0
COMPASS_DEC : 0.0

COMPASS_DIA_X : 0.999
COMPASS_DIA_Y : 0.999
COMPASS_DIA_Z : 0.999

COMPASS_ODI_X : 0.001
COMPASS_ODI_Y : 0.001
COMPASS_ODI_Z : 0.001

COMPASS_OFS_X : 0.001
COMPASS_OFS_Y : 0.001
COMPASS_OFS_Z : 0.001

# Use HITL IMU
AHRS_TRIM_X : 0.000214698069612496
AHRS_TRIM_Y : 0.000064728621509857
AHRS_TRIM_Z : 0.000000000000000000

# CUAV X7 SPI INS devid=3211786 bus_type=2 (SPI), bus=1, address=2 devtype=49
# DroneCAN Accel devid=3997955 bus_type=3 (BUS_TYPE_UAVCAN), bus=0, address=1 devtype=61 (DEVTYPE_UAVCAN)
# DroneCAN Gyro devid=3998211 bus_type=3 (BUS_TYPE_UAVCAN), bus=0, address=2 devtype=61 (DEVTYPE_UAVCAN)
INS_ACC1_CALTEMP : 0.000
INS_ACCOFFS_X : 0.001
INS_ACCOFFS_Y : 0.001
INS_ACCOFFS_Z : 0.001
INS_ACCSCAL_X : 0.999
INS_ACCSCAL_Y : 0.999
INS_ACCSCAL_Z : 0.999

INS_GYR1_CALTEMP : 0.000
INS_GYROFFS_X : 0.001
INS_GYROFFS_Y : 0.001
INS_GYROFFS_Z : 0.001
1 change: 1 addition & 0 deletions configs/dynamics/quadcopter_ardupilot/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
# ArduPilot Quadcopter
40 changes: 40 additions & 0 deletions configs/dynamics/quadcopter_ardupilot/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
vehicle_mass : 2.0 # kg

# This represents the response time of the motor to changes in input for brushless motors with ESCs
# Higher-quality ESCs and motors may have a faster response (closer to 0.02 sec).
# Slower or less efficient systems may be closer to 0.05 sec.
motor_time_constant: 0.02 # sec

# For a standard 10–12 inch propeller
# This is the rotational inertia of the motor and propeller system.
# It depends on the size and weight of the propeller and motor rotor:
# Typical value: 0.00002–0.00006 kg·m²
# Smaller drones with lighter props will have lower values.
motor_rotational_inertia: 6.62e-6 # kg m^2
thrust_coefficient: 1.91e-6 # N/(rad/s)^2"
torque_coefficient: 2.6e-7 # Nm/(rad/s)^2
drag_coefficient: 0.1 # N/(m/s)
aeromoment_coefficient_xx: 0.003 # Nm/(rad/s)^2
aeromoment_coefficient_yy: 0.003 # Nm/(rad/s)^2
aeromoment_coefficient_zz: 0.003 # Nm/(rad/s)^2
vehicle_inertia_xx: 0.045 # kg * m^2
vehicle_inertia_yy: 0.045 # kg * m^2

# Low value -> the yaw oscillations.
# High value -> slow response on yaw inputs and it may feel "lazy" in maintaining the commanded yaw angle.
vehicle_inertia_zz: 0.045 # kg * m^2

max_prop_speed: 2200 # rad/s
moment_process_noise: 1.25e-7 # (Nm)^2 s
force_process_noise: 0.0005 # N^2 s"

# The perpendicular distance between a force's line of action (such as thrust
# or lift) and the center of mass (or the axis of rotation) of the UAV
moment_arm: 0.35 # m

accelerometer_biasprocess: 0.0 # m^2/s^5, 1.0e-7
gyroscope_biasprocess: 0.0 # rad^2/s^3, 1.0e-7
accelerometer_biasinitvar: 0.00001 # (m/s^2)^2, 0.005
gyroscope_biasinitvar: 0.00001 # (rad/s)^2, 0.003
accelerometer_variance: 0.0001 # m^2/s^4, 0.001
gyroscope_variance: 0.00001 # rad^2/s^2, 0.001
5 changes: 5 additions & 0 deletions configs/vehicles/ap_copter_v4_5_7_dronecan.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
params:
mode: dronecan
alias: ac
sim_config: ap_copter_v4_5_7_dronecan
info: ""
15 changes: 15 additions & 0 deletions scripts/run_sim.sh
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,18 @@ px4_v1_15_0_dronecan_quadrotor() {
dynamics:=quadcopter
}

ap_copter_v4_5_7_dronecan() {
setup_ros
setup_dronecan_hitl
$SCRIPT_DIR/airframe_printer.sh 4001
roslaunch innopolis_vtol_dynamics hitl.launch \
run_dronecan_communicator:=true \
logging_type:=quadcopter \
vehicle_params:=$DYNAMICS_CONFIGS_DIR/quadcopter_ardupilot/params.yaml \
mixer:=direct_mixer \
dynamics:=quadcopter
}

px4_v1_15_0_cyphal_quadcopter() {
setup_ros
setup_cyphal_hitl
Expand Down Expand Up @@ -203,13 +215,16 @@ fi
SCRIPT_DIR="$(dirname "$0")"
REPO_DIR="$(dirname "$SCRIPT_DIR")"
VEHICLE_PARAMS_DIR=$REPO_DIR/uav_dynamics/uav_hitl_dynamics/config/vehicle_params
DYNAMICS_CONFIGS_DIR=$REPO_DIR/configs/dynamics

if [ "$1" = "px4_v1_15_0_dronecan_quadplane_vtol" ]; then
px4_v1_15_0_dronecan_quadplane_vtol
elif [ "$1" = "px4_v1_13_0_dronecan_vtol" ]; then
px4_v1_13_0_dronecan_vtol
elif [ "$1" = "px4_v1_15_0_dronecan_quadrotor" ]; then
px4_v1_15_0_dronecan_quadrotor
elif [ "$1" = "ap_copter_v4_5_7_dronecan" ]; then
ap_copter_v4_5_7_dronecan
elif [ "$1" = "px4_v1_15_0_cyphal_quadcopter" ]; then
px4_v1_15_0_cyphal_quadcopter
elif [ "$1" = "px4_v1_15_0_cyphal_octorotor" ]; then
Expand Down
Loading