Skip to content

Commit

Permalink
add cyphal vtol octoplane coaxial
Browse files Browse the repository at this point in the history
  • Loading branch information
PonomarevDA committed Dec 10, 2023
1 parent 559c5b7 commit 81b25e7
Show file tree
Hide file tree
Showing 9 changed files with 177 additions and 10 deletions.
9 changes: 9 additions & 0 deletions configs/px4/v1.14/vtol_octoplane_coaxial/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Generic Standard VTOL (13000)

## Airframe

<img src="https://docs.px4.io/main/assets/img/VTOLPlane.2ffc44a4.svg" alt="drawing" width="240"/>

## Actuators Setup

<img src="https://raw.githubusercontent.com/RaccoonlabDev/innopolis_vtol_dynamics/docs/assets/configs/px4_v1.14_standard_vtol.png" alt="drawing" width="480"/>
22 changes: 22 additions & 0 deletions configs/px4/v1.14/vtol_octoplane_coaxial/airframe.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
SYS_AUTOSTART: 13000

FW_AIRSPD_MAX: 30.0 # Max Airspeed (CAS)
FW_AIRSPD_TRIM: 25.0 # Trim (Cruise) Airspeed (CAS)
FW_AIRSPD_MIN: 20.0 # Minimum Airspeed (CAS)
FW_AIRSPD_STALL: 18.0 # Stall Airspeed (CAS)
NAV_LOITER_RAD: 150.0 # Loiter radius (FW only)
FW_YR_P: 0.5 # Yaw rate proportional rate
FW_THR_TRIM: 0.38 # Trim throttle
VT_ARSP_TRANS: 18.0 # Airspeed at which we can switch to fw mode
VT_F_TRANS_DUR: 10.0 # Time in seconds used for a transition. Default 5.0
VT_F_TRANS_THR: 0.8 # Target throttle value for the transition to fixed-wing flight. Default 1.0
SENS_DPRES_OFF: 1.0

FW_R_LIM: 35.0 # Default 50.0 that is out of max angle supported by the vtol dynamics
FW_R_RMAX: 30.0 # Default 70.0
FW_P_RMAX_NEG: 30.0 # Default 60.0
FW_P_RMAX_POS: 30.0 # Default 60.0

MC_YAWRATE_P: 1.0 # Yaw rate P gain. Default 0.2. Max 0.6.

VT_B_TRANS_RAMP: 10.0 # Back transition MC motor ramp up time. Default 3.0 sec.
18 changes: 18 additions & 0 deletions configs/px4/v1.14/vtol_octoplane_coaxial/cyphal.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
UCAN1_ESC_FUNC1: 101 # motor 1
UCAN1_ESC_FUNC2: 102 # motor 2
UCAN1_ESC_FUNC3: 103 # motor 3
UCAN1_ESC_FUNC4: 104 # motor 4
UCAN1_ESC_FUNC5: 105 # motor 5
UCAN1_ESC_FUNC6: 106 # motor 6
UCAN1_ESC_FUNC7: 107 # motor 7
UCAN1_ESC_FUNC8: 108 # motor 8
UCAN1_ESC_FUNC9: 109 # motor 9
UCAN1_ESC_FUNC10: 201 # servo 1 (left aileron)
UCAN1_ESC_FUNC11: 202 # servo 2 (right aileron)
UCAN1_ESC_FUNC12: 203 # servo 3 (elevators)
UCAN1_ESC_FUNC13: 204 # servo 4 (rudders)

UCAN1_FB4_SUB: 2504
UCAN1_FB5_SUB: 2505
UCAN1_FB6_SUB: 2506
UCAN1_FB7_SUB: 2507
9 changes: 9 additions & 0 deletions configs/px4/v1.14/vtol_octoplane_coaxial/dronecan.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
UAVCAN_EC_FUNC1: 101 # motor 1
UAVCAN_EC_FUNC2: 102 # motor 2
UAVCAN_EC_FUNC3: 103 # motor 3
UAVCAN_EC_FUNC4: 104 # motor 4
UAVCAN_EC_FUNC5: 105 # motor 5
UAVCAN_SV_FUNC1: 201 # servo 1 (left aileron)
UAVCAN_SV_FUNC2: 202 # servo 2 (right aileron)
UAVCAN_SV_FUNC3: 203 # servo 3 (elevators)
UAVCAN_SV_FUNC4: 204 # servo 4 (rudders)
73 changes: 73 additions & 0 deletions configs/px4/v1.14/vtol_octoplane_coaxial/geometry.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
CA_ROTOR_COUNT: 9 # Total number of motors

CA_ROTOR0_AX: 0.0
CA_ROTOR0_AY: 0.0
CA_ROTOR0_AZ: -1.0
CA_ROTOR0_KM: 0.05
CA_ROTOR0_PX: 1.0
CA_ROTOR0_PY: 1.0
CA_ROTOR0_PZ: 0.0

CA_ROTOR1_AX: 0.0
CA_ROTOR1_AY: 0.0
CA_ROTOR1_AZ: -1.0
CA_ROTOR1_KM: 0.05
CA_ROTOR1_PX: -1.0
CA_ROTOR1_PY: -1.0
CA_ROTOR1_PZ: 0.0

CA_ROTOR2_AX: 0.0
CA_ROTOR2_AY: 0.0
CA_ROTOR2_AZ: -1.0
CA_ROTOR2_KM: -0.05
CA_ROTOR2_PX: 1.0
CA_ROTOR2_PY: -1.0
CA_ROTOR2_PZ: 0.0

CA_ROTOR3_AX: 0.0
CA_ROTOR3_AY: 0.0
CA_ROTOR3_AZ: -1.0
CA_ROTOR3_KM: -0.05
CA_ROTOR3_PX: -1.0
CA_ROTOR3_PY: 1.0
CA_ROTOR3_PZ: 0.0

CA_ROTOR4_AX: 0.0
CA_ROTOR4_AY: 0.0
CA_ROTOR4_AZ: -1.0
CA_ROTOR4_KM: 0.05
CA_ROTOR4_PX: 1.0
CA_ROTOR4_PY: 1.0
CA_ROTOR4_PZ: 0.0

CA_ROTOR5_AX: 0.0
CA_ROTOR5_AY: 0.0
CA_ROTOR5_AZ: -1.0
CA_ROTOR5_KM: 0.05
CA_ROTOR5_PX: -1.0
CA_ROTOR5_PY: -1.0
CA_ROTOR5_PZ: 0.0

CA_ROTOR6_AX: 0.0
CA_ROTOR6_AY: 0.0
CA_ROTOR6_AZ: -1.0
CA_ROTOR6_KM: -0.05
CA_ROTOR6_PX: 1.0
CA_ROTOR6_PY: -1.0
CA_ROTOR6_PZ: 0.0

CA_ROTOR7_AX: 0.0
CA_ROTOR7_AY: 0.0
CA_ROTOR7_AZ: -1.0
CA_ROTOR7_KM: -0.05
CA_ROTOR7_PX: -1.0
CA_ROTOR7_PY: 1.0
CA_ROTOR7_PZ: 0.0

CA_ROTOR8_AX: 1.0
CA_ROTOR8_AY: 0.0
CA_ROTOR8_AZ: 0.0
CA_ROTOR8_KM: 0.05
CA_ROTOR8_PX: 0.0
CA_ROTOR8_PY: 0.0
CA_ROTOR8_PZ: 0.0
12 changes: 12 additions & 0 deletions scripts/configure.sh
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,16 @@ px4_v1_14_0_beta_cyphal_vtol() {
${REPOSITORY_DIR}/configs/px4/common.yaml
}

px4_v1_14_0_beta_cyphal_vtol_8_motors() {
wget -O $DOWNLOADED_BINARY_PATH $PX4_V1_14_0_BETA_CYPHAL_URL
autopilot-configurator -v --firmware $DOWNLOADED_BINARY_PATH -f --config \
${REPOSITORY_DIR}/configs/px4/v1.14/vtol_octoplane_coaxial/airframe.yaml \
${REPOSITORY_DIR}/configs/px4/v1.14/vtol_octoplane_coaxial/cyphal.yaml \
${REPOSITORY_DIR}/configs/px4/v1.14/vtol_octoplane_coaxial/geometry.yaml \
${REPOSITORY_DIR}/configs/px4/cyphal.yaml \
${REPOSITORY_DIR}/configs/px4/common.yaml
}

if [ -z $1 ]; then
printf "$RED$SCRIPT_NAME ERROR (line ${LINENO}): Argument is not specified!$NC\n"
exit 1
Expand Down Expand Up @@ -109,6 +119,8 @@ elif [[ $1 == "px4_v1_14_0_beta_dronecan_vtol" ]]; then
px4_v1_14_0_beta_dronecan_vtol
elif [[ $1 == "px4_v1_14_0_beta_cyphal_vtol" ]]; then
px4_v1_14_0_beta_cyphal_vtol
elif [[ $1 == "px4_v1_14_0_beta_cyphal_vtol_8_motors" ]]; then
px4_v1_14_0_beta_cyphal_vtol_8_motors
else
printf "$RED$SCRIPT_NAME ERROR (line ${LINENO}): Unknown argument: '$1' $NC\n"
exit 1
Expand Down
17 changes: 13 additions & 4 deletions scripts/docker.sh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ Supported modes (with aliases):
-------------------------------------------------------------------------------
cyphal_quadrotor,cq | Cyphal PX4 v1.14-beta Quadrotor x (4001)
cyphal_standard_vtol,csv | Cyphal PX4 v1.14-beta Standard VTOL (13000)
cyphal_vtol_8_motors,cv8 | Cyphal PX4 v1.14-beta VTOL 8 motors (13050)
dronecan_quadrotor,dq | DroneCAN PX4 v1.14-beta Quadrotor (4001)
dronecan_vtol_v1_14_0,dv | DroneCAN PX4 v1.14-beta Standard VTOL (13000)
dronecan_vtol_v1_12_1,dvo | DroneCAN PX4 v1.12 vtol 13070
Expand All @@ -26,8 +27,6 @@ Supported modes (with aliases):
sitl_flight_goggles | MAVLink PX4 v1.12 Quadrotor (4001)
cyphal_and_dronecan | 2 CAN AP v4.4.0 Copter
-------------------------------------------------------------------------------
cyphal_vtol_octoplane,cvo | Cyphal PX4 v1.14-beta VTOL Octoplane (13050)
-------------------------------------------------------------------------------
Commands (with aliases):
build,b Build docker image
Expand Down Expand Up @@ -222,6 +221,16 @@ cyphal_standard_vtol() {
docker container run --rm $DOCKER_FLAGS $IMAGE_NAME ./scripts/run_sim.sh cyphal_standard_vtol
}

cyphal_vtol_8_motors() {
kill_all_related_containers
setup_cyphal_hitl_config
slcan_checker&
if [[ $OPTIONS == "--force" ]]; then
./configure.sh px4_v1_14_0_beta_cyphal_vtol_8_motors
fi
docker container run --rm $DOCKER_FLAGS $IMAGE_NAME ./scripts/run_sim.sh cyphal_vtol_8_motors
}

cyphal_and_dronecan_inno_vtol() {
echo "Cyphal and DroneCAN mode is a special mode that uses:"
echo "- slcan0 based on the 1-st sniffer for DroneCAN communication (sensors)"
Expand Down Expand Up @@ -278,8 +287,8 @@ elif [ "$1" = "cyphal_octorotor" ] || [ "$1" = "co" ]; then
cyphal_octorotor
elif [ "$1" = "cyphal_standard_vtol" ] || [ "$1" = "csv" ]; then
cyphal_standard_vtol
elif [ "$1" = "cyphal_vtol_octoplane" ] || [ "$1" = "cvo" ]; then
echo "Not ready yet" # cyphal_vtol_octoplane
elif [ "$1" = "cyphal_vtol_8_motors" ] || [ "$1" = "cv8" ]; then
cyphal_vtol_8_motors
elif [ "$1" = "cyphal_and_dronecan" ]; then
cyphal_and_dronecan_inno_vtol
elif [ "$1" = "interactive" ] || [ "$1" = "i" ]; then
Expand Down
25 changes: 20 additions & 5 deletions scripts/run_sim.sh
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/bin/bash

print_help() {
echo "Wrapper under ROS API for Innopolis VTOL Dynamics simulator.
echo "Wrapper under ROS API for UAV Dynamics simulator.
It automatically run all auxilliary scripts required to each specific mode and source necessary setup.bash files.
It supports all possible simulator modes.
Expand All @@ -15,12 +15,13 @@ Commands:
dronecan_flight_goggles Run dynamics simulator in DroneCan HITL mode for flight_goggles airframe
cyphal_quadrotor Cyphal HITL PX4 Quadrotor (4001)
cyphal_octorotor Cyphal HITL PX4 Octorotor (12001)
cyphal_standard_vtol Run dynamics simulator in Cyphal HITL mode for inno_vtol airframe.
cyphal_and_dronecan_inno_vtol Run dynamics simulator in DroneCan + Cyphal mode for inno_vtol airframe.
cyphal_standard_vtol Run dynamics simulator in Cyphal HITL mode for vtol 4 motors airframe.
cyphal_vtol_8_motors Run dynamics simulator in Cyphal HITL mode for vtol 8 motors airframe.
cyphal_and_dronecan_inno_vtol Run dynamics simulator in DroneCan + Cyphal mode for vtol airframe.
This mode uses 2 serial ports and is in the alpha testing stage yet.
sitl_inno_vtol Run dynamics simulator in MAVLink SITL mode for inno_vtol airframe
sitl_inno_vtol Run dynamics simulator in MAVLink SITL mode for vtol airframe
sitl_flight_goggles Run dynamics simulator in MAVLink SITL mode for flight_goggles airframe
sitl_inno_vtol_with_flight_stack Run dynamics simulator in MAVLink SITL mode for inno_vtol airframe (with additional including px4.launch)
sitl_inno_vtol_with_flight_stack Run dynamics simulator in MAVLink SITL mode for vtol airframe (with additional including px4.launch)
sitl_flight_goggles_with_flight_stack Run dynamics simulator in MAVLink SITL mode for flight_goggles airframe (with additional including px4.launch)
Auxilliary commands:
Expand Down Expand Up @@ -155,6 +156,18 @@ cyphal_standard_vtol() {
dynamics:=vtol_dynamics
}

cyphal_vtol_8_motors() {
setup_ros
setup_cyphal_hitl
$SCRIPT_DIR/airframe_printer.sh 13000
roslaunch innopolis_vtol_dynamics hitl.launch \
run_cyphal_communicator:=true \
logging_type:=vtol_8_motors_logger \
vehicle_params:=vtol_tfm15 \
mixer:=px4_v1_14_0_vtol_13000_8_motors_mixer \
dynamics:=vtol_dynamics
}

cyphal_and_dronecan_inno_vtol() {
setup_ros
setup_combined_hitl
Expand Down Expand Up @@ -233,6 +246,8 @@ elif [ "$1" = "cyphal_octorotor" ]; then
cyphal_octorotor
elif [ "$1" = "cyphal_standard_vtol" ]; then
cyphal_standard_vtol
elif [ "$1" = "cyphal_vtol_8_motors" ]; then
cyphal_vtol_8_motors
elif [ "$1" = "cyphal_and_dronecan_inno_vtol" ]; then
cyphal_and_dronecan_inno_vtol
elif [ "$1" = "sitl_inno_vtol" ]; then
Expand Down
2 changes: 1 addition & 1 deletion uav_dynamics/inno_vtol_dynamics

0 comments on commit 81b25e7

Please sign in to comment.