-
Notifications
You must be signed in to change notification settings - Fork 8
/
run_sim.sh
executable file
·246 lines (223 loc) · 9.44 KB
/
run_sim.sh
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
#!/bin/bash
print_help() {
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.
https://github.com/ZilantRobotics/innopolis_vtol_dynamics
Usage: run_sim.sh <command>
Commands:
px4_v1_15_0_dronecan_quadplane_vtol Run dynamics simulator in DroneCan HITL mode for px4 vtol 13000 airframe
px4_v1_13_0_dronecan_vtol Run dynamics simulator in DroneCan HITL mode for px4 vtol 13070 airframe
px4_v1_15_0_dronecan_quadrotor Run dynamics simulator in DroneCan HITL mode for flight_goggles airframe
px4_v1_15_0_cyphal_quadcopter Cyphal HITL PX4 Quadrotor (4001)
px4_v1_15_0_cyphal_octorotor Cyphal HITL PX4 Octorotor (12001)
px4_v1_15_0_cyphal_quadplane_vtol Run dynamics simulator in Cyphal HITL mode for vtol 4 motors airframe.
px4_v1_15_0_cyphal_octoplane_vtol 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.
px4_v1_15_0_mavlink_quadplane_vtol Run dynamics simulator in MAVLink SITL mode for vtol airframe
px4_v1_15_0_mavlink_quadcopter Run dynamics simulator in MAVLink SITL mode for flight_goggles airframe
Auxilliary commands:
ros Source ROS and catkin_ws setup.bash files
help Print this message and exit"
}
setup_ros() {
# /opt/ros/$ROS_DISTRO/setup.bash should be either run first, or not run at all
# If catkin_ws is not found, do nothing.
DOCKER_CATKIN_WS_SETUP_BASH_PATH=/catkin_ws/devel/setup.bash
MOST_PROBABLE_CATKIN_WS_SETUP_BASH_PATH=~/catkin_ws/devel/setup.bash
if [ -f "$DOCKER_CATKIN_WS_SETUP_BASH_PATH" ]; then
source /opt/ros/$ROS_DISTRO/setup.bash
source $DOCKER_CATKIN_WS_SETUP_BASH_PATH
elif [ -f "$MOST_PROBABLE_CATKIN_WS_SETUP_BASH_PATH" ]; then
source /opt/ros/$ROS_DISTRO/setup.bash
source $MOST_PROBABLE_CATKIN_WS_SETUP_BASH_PATH
fi
}
setup_dronecan_hitl() {
if [ ! -z $DRONECAN_DEV_PATH_SYMLINK ]; then
echo "Trying to create slcan0 for dronecan..."
$SCRIPT_DIR/create_slcan.sh -d $DRONECAN_DEV_PATH_SYMLINK -i slcan0
fi
if [[ -z $(ifconfig | grep slcan0) ]]; then
echo "HITL can't be started without CAN interface!"
exit 0
fi
}
setup_cyphal_hitl() {
if [ ! -z $CYPHAL_DEV_PATH_SYMLINK ]; then
echo "Trying to create slcan0 for cyphal/serial..."
$SCRIPT_DIR/create_slcan.sh -d $CYPHAL_DEV_PATH_SYMLINK -i slcan0
fi
if [[ -z $(ifconfig | grep slcan0) ]]; then
echo "HITL can't be started without CAN interface!"
exit 0
fi
source $SCRIPT_DIR/cyphal_config_slcan0.sh
}
setup_combined_hitl() {
if [ ! -z $DRONECAN_DEV_PATH_SYMLINK ]; then
echo "Trying to create slcan0 for comined HITL: dronecan..."
$SCRIPT_DIR/create_slcan.sh -d $DRONECAN_DEV_PATH_SYMLINK -i slcan0
fi
if [ ! -z $CYPHAL_DEV_PATH_SYMLINK ]; then
echo "Trying to create slcan1 for comined HITL: cyphal..."
$SCRIPT_DIR/create_slcan.sh -d $CYPHAL_DEV_PATH_SYMLINK -i slcan1
source $SCRIPT_DIR/cyphal_config_slcan1.sh
fi
}
px4_v1_15_0_dronecan_quadplane_vtol() {
setup_ros
setup_dronecan_hitl
$SCRIPT_DIR/airframe_printer.sh 13000
roslaunch innopolis_vtol_dynamics hitl.launch \
run_dronecan_communicator:=true \
logging_type:=standard_vtol \
vehicle_params:=$VEHICLE_PARAMS_DIR/vtol_7kg/params.yaml \
mixer:=px4_v1_14_0_vtol_13000_mixer \
dynamics:=vtol_dynamics
}
px4_v1_13_0_dronecan_vtol() {
setup_ros
setup_dronecan_hitl
$SCRIPT_DIR/airframe_printer.sh 13000
roslaunch innopolis_vtol_dynamics hitl.launch \
run_dronecan_communicator:=true \
logging_type:=standard_vtol \
vehicle_params:=$VEHICLE_PARAMS_DIR/vtol_7kg/params.yaml \
mixer:=vtol_13070_mixer \
dynamics:=vtol_dynamics
}
px4_v1_15_0_dronecan_quadrotor() {
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_hany/params.yaml \
mixer:=direct_mixer \
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
$SCRIPT_DIR/airframe_printer.sh 4001
roslaunch innopolis_vtol_dynamics hitl.launch \
run_cyphal_communicator:=true \
logging_type:=quadcopter \
vehicle_params:=$DYNAMICS_CONFIGS_DIR/quadcopter_hany/params.yaml \
mixer:=direct_mixer \
dynamics:=quadcopter
}
px4_v1_15_0_cyphal_octorotor() {
setup_ros
setup_cyphal_hitl
$SCRIPT_DIR/airframe_printer.sh 12001
roslaunch innopolis_vtol_dynamics hitl.launch \
run_cyphal_communicator:=true \
logging_type:=quadcopter \
vehicle_params:=$VEHICLE_PARAMS_DIR/octorotor/params.yaml \
mixer:=direct_mixer \
dynamics:=octorotor
}
px4_v1_15_0_cyphal_quadplane_vtol() {
setup_ros
setup_cyphal_hitl
$SCRIPT_DIR/airframe_printer.sh 13000
roslaunch innopolis_vtol_dynamics hitl.launch \
run_cyphal_communicator:=true \
logging_type:=standard_vtol \
vehicle_params:=$VEHICLE_PARAMS_DIR/vtol_7kg/params.yaml \
mixer:=px4_v1_14_0_vtol_13000_mixer \
dynamics:=vtol_dynamics
}
px4_v1_15_0_cyphal_octoplane_vtol() {
setup_ros
setup_cyphal_hitl
$SCRIPT_DIR/airframe_printer.sh 13050
roslaunch innopolis_vtol_dynamics hitl.launch \
run_cyphal_communicator:=true \
logging_type:=vtol_8_motors_logger \
vehicle_params:=$VEHICLE_PARAMS_DIR/vtol_tfm15/params.yaml \
mixer:=px4_v1_14_0_vtol_13000_8_motors_mixer \
dynamics:=vtol_dynamics
}
cyphal_and_dronecan_inno_vtol() {
setup_ros
setup_combined_hitl
$SCRIPT_DIR/airframe_printer.sh 4001
roslaunch innopolis_vtol_dynamics hitl.launch \
run_cyphal_communicator:=true \
run_dronecan_communicator:=true \
logging_type:=quadcopter \
vehicle_params:=$VEHICLE_PARAMS_DIR/quadrotor_ardupilot/params.yaml \
mixer:=direct_mixer \
dynamics:=quadcopter
}
px4_v1_15_0_mavlink_quadplane_vtol() {
setup_ros
roslaunch innopolis_vtol_dynamics sitl.launch \
logging_type:=standard_vtol \
sitl_vehicle:=innopolis_vtol \
vehicle_params:=$VEHICLE_PARAMS_DIR/vtol_7kg/params.yaml \
mixer:=px4_v1_14_0_vtol_13000_mixer \
dynamics:=vtol_dynamics \
run_sitl_flight_stack:="false"
}
px4_v1_15_0_mavlink_quadcopter() {
setup_ros
roslaunch innopolis_vtol_dynamics sitl.launch \
logging_type:=quadcopter \
sitl_vehicle:=iris \
vehicle_params:=$DYNAMICS_CONFIGS_DIR/quadcopter_iris_px4/params.yaml \
mixer:=direct_mixer \
dynamics:=quadcopter \
run_sitl_flight_stack:="false"
}
# Entry point
if [ "${BASH_SOURCE[0]}" -ef "$0" ]; then
set -e
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
px4_v1_15_0_cyphal_octorotor
elif [ "$1" = "px4_v1_15_0_cyphal_quadplane_vtol" ]; then
px4_v1_15_0_cyphal_quadplane_vtol
elif [ "$1" = "px4_v1_15_0_cyphal_octoplane_vtol" ]; then
px4_v1_15_0_cyphal_octoplane_vtol
elif [ "$1" = "cyphal_and_dronecan_inno_vtol" ]; then
cyphal_and_dronecan_inno_vtol
elif [ "$1" = "px4_v1_15_0_mavlink_quadplane_vtol" ]; then
px4_v1_15_0_mavlink_quadplane_vtol
elif [ "$1" = "px4_v1_15_0_mavlink_quadcopter" ]; then
px4_v1_15_0_mavlink_quadcopter
elif [ "$1" = "ros" ]; then
setup_ros
else
print_help
fi