Skip to content

Commit

Permalink
tested once
Browse files Browse the repository at this point in the history
  • Loading branch information
PonomarevDA committed Dec 9, 2024
1 parent 052df79 commit 578db0f
Show file tree
Hide file tree
Showing 4 changed files with 130 additions and 6 deletions.
88 changes: 88 additions & 0 deletions configs/ardupilot_dronecan_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
FRAME_CLASS : 1.0 # Quadcopter
CAN_D1_PROTOCOL : 1.0 # DroneCAN
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

CAN_D1_UC_ESC_BM : 15.0 # For a Quadcopter

# 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

# Use HITL Compass
# bus_type : 3;
# bus: 5; // which instance of the bus type
# address; // address on the bus (eg. I2C address)
# devtype; // device class specific device type
# uint32_t gyro_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, bus_id, 1, DEVTYPE_UAVCAN);
# BUS_TYPE_UAVCAN = 3
# DEVTYPE_UAVCAN = 0x3D
# ID = bus_type * (1 << 0) + bus * (1 << 3) + address * (1 << 8) + devtype * (1 << 8)
# bus_type = devid % 8 = 3
# bus = (devid >> 3) % 32 = 64
# address = (devid >> 8) % 256 = 42
# devtype = (devid >> 16) % 256 = 1 = 0x3D

# 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
# INS devid=3211786 bus_type=2 (CAN), bus=1, address=2 devtype=49

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

# INS
# Use DroneCAN HITL IMU: accel=3997955, gyro=3998211.
# bus_type = devid % 8 = 3
# bus = (devid >> 3) % 32 = 64
# address = (devid >> 8) % 256 = 42
# devtype = (devid >> 16) % 256 = 1 = 0x3D
# 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
26 changes: 21 additions & 5 deletions configs/dynamics/quadcopter_ardupilot/params.yaml
Original file line number Diff line number Diff line change
@@ -1,20 +1,36 @@
vehicle_mass : 1.5 # kg
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.0100 #
vehicle_inertia_yy: 0.0100 #
vehicle_inertia_zz: 0.0150 #
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"

moment_arm: 0.08 # m
# 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
Expand Down
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: ""
17 changes: 16 additions & 1 deletion 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 @@ -189,7 +201,7 @@ px4_v1_15_0_mavlink_quadcopter() {
roslaunch innopolis_vtol_dynamics sitl.launch \
logging_type:=quadcopter \
sitl_vehicle:=iris \
vehicle_params:=$REPO_DIR/configs/dynamics/quadcopter_iris_px4/params.yaml \
vehicle_params:=$DYNAMICS_CONFIGS_DIR/quadcopter_iris_px4/params.yaml \
mixer:=direct_mixer \
dynamics:=quadcopter \
run_sitl_flight_stack:="false"
Expand All @@ -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

0 comments on commit 578db0f

Please sign in to comment.