Skip to content
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
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,7 @@ Once done, detach Tmux (and remove the containers) with `Ctrl + b`, then `d`
- The simulation (SITL or HITL) container must start after the aircraft ones for Gstreamer to pick up the UDP streams
- wmctrl does not work as-is in WSLg
- QGC is started with a virtual joystick (with low throttle if using only VTOLs and centered throttle if there are quads), this is reflective of real-life but note that this counts as "RC loss" when switching focus from one autopilot instance to another
- ArduPilot CIRCLE mode for quads require to explicitly center the virtual throttle with 'rc 3 1500' to keep altitude, QGC virtual joystick can interfere
- ArduPilot CIRCLE mode for quads require to explicitly center the throttle with 'rc 3 1500' to keep altitude, QGC virtual joystick can interfere
- Gazebo WindEffects plugin is disabled/not working for PX4 standard_vtol
- Command 178 MAV_CMD_DO_CHANGE_SPEED is accepted but not effective in changing speed for ArduPilot VTOL
- ArduPilot SITL for Iris uses option -f that also sets "external": True, this is not the case for the Alti Transition from ArduPilot/SITL_Models
Expand Down
4 changes: 2 additions & 2 deletions aircraft/aircraft.yml.erb
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ windows:
- >
<% if simulated_time == 'true' %>
sudo sed -i '0,/ros__parameters:/s/ros__parameters:/ros__parameters:\n use_sim_time: true/' /opt/ros/humble/share/mavros/launch/apm_config.yaml &&
ros2 launch mavros apm.launch fcu_url:=udp://0.0.0.0:<%= 22530 + drone_id - 1 %>@<%= 22530 + drone_id - 1 %> tgt_system:=<%= drone_id %>
ros2 launch mavros apm.launch fcu_url:=udp://<%= subnet_prefix %>.1.<%= drone_id %>:8888@8888 tgt_system:=<%= drone_id %>
<% else %>
python3 /aas/aircraft_resources/patches/request_mavlink_streams.py --device '/dev/ttyTHS1' --baudrate 921600 --target-system <%= drone_id %> --target-component 1 --rate 4 &&
ros2 launch mavros apm.launch fcu_url:=/dev/ttyTHS1:921600 tgt_system:=<%= drone_id %>
Expand Down Expand Up @@ -78,4 +78,4 @@ windows:
layout: tiled
panes:
- mkdir -p /aas/rosbags && cd /aas/rosbags && ros2 bag record -a
<% end %>
<% end %>
17 changes: 8 additions & 9 deletions scripts/sim_run.sh
Original file line number Diff line number Diff line change
Expand Up @@ -126,9 +126,6 @@ XTERM_CONFIG_ARGS=(
Ctrl Shift <Key>V: insert-selection(CLIPBOARD)'
)

# Initialize a counter for the drone IDs
DRONE_ID=0 # 0: simulation, 1-N: drones

# Launch the simulation container
DOCKER_CMD="docker run -it --rm \
--volume /tmp/.X11-unix:/tmp/.X11-unix:rw --device /dev/dri --gpus all \
Expand All @@ -151,18 +148,19 @@ if [[ "$DESK_ENV" == "wsl" ]]; then
DOCKER_CMD="$DOCKER_CMD $WSL_OPTS"
fi
DOCKER_CMD="$DOCKER_CMD ${MODE_SIM_OPTS} simulation-image"
calculate_terminal_position $DRONE_ID
calculate_terminal_position 0
xterm "${XTERM_CONFIG_ARGS[@]}" -title "Simulation" -fa Monospace -fs $FONT_SIZE -bg black -fg white -geometry "${TERM_COLS}x${TERM_ROWS}+${X_POS}+${Y_POS}" -hold -e bash -c "$DOCKER_CMD" &

if [[ "$HITL" == "false" ]]; then
# Initialize a counter for the drone IDs
DRONE_ID=1 # 1, 2, .., N drones

# Function to launch the aircraft containers
launch_aircraft_containers() {
local drone_type=$1
local num_drones=$2
local type_label=$3

for i in $(seq 1 $num_drones); do
DRONE_ID=$((DRONE_ID + 1))
sleep 1.5 # Limit resource usage
DOCKER_CMD="docker run -it --rm \
--volume /tmp/.X11-unix:/tmp/.X11-unix:rw --device /dev/dri --gpus all \
Expand All @@ -181,13 +179,14 @@ if [[ "$HITL" == "false" ]]; then
fi
DOCKER_CMD="$DOCKER_CMD ${MODE_AIR_OPTS} aircraft-image"
calculate_terminal_position $DRONE_ID
xterm "${XTERM_CONFIG_ARGS[@]}" -title "$type_label $DRONE_ID" -fa Monospace -fs $FONT_SIZE -bg black -fg white -geometry "${TERM_COLS}x${TERM_ROWS}+${X_POS}+${Y_POS}" -hold -e bash -c "$DOCKER_CMD" &
xterm "${XTERM_CONFIG_ARGS[@]}" -title "${drone_type^^} $DRONE_ID" -fa Monospace -fs $FONT_SIZE -bg black -fg white -geometry "${TERM_COLS}x${TERM_ROWS}+${X_POS}+${Y_POS}" -hold -e bash -c "$DOCKER_CMD" &
DRONE_ID=$((DRONE_ID + 1))
done
}
# Launch the Quad containers
launch_aircraft_containers "quad" $NUM_QUADS "Quad"
launch_aircraft_containers "quad" $NUM_QUADS
# Launch the VTOL containers
launch_aircraft_containers "vtol" $NUM_VTOLS "VTOL"
launch_aircraft_containers "vtol" $NUM_VTOLS
fi

echo "Fly, my pretties, fly!"
Expand Down
150 changes: 56 additions & 94 deletions simulation/simulation.yml.erb
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ windows:
panes:
- clear && echo "So nice to have you with us, this is the simulation container."

<% if autopilot == 'px4' %>
- gz_sim:
layout: main-vertical
panes:
Expand All @@ -29,37 +28,21 @@ windows:
<% if lidar == 'false' %>
sed -i '/<sensor/,/<\/sensor>/d' /aas/simulation_resources/aircraft_models/sensor_lidar/model.sdf &&
<% end %>
GZ_SIM_RESOURCE_PATH=$GZ_SIM_RESOURCE_PATH:/aas/simulation_resources/aircraft_models:/aas/simulation_resources/simulation_worlds
GZ_SIM_PHYSICS_ENGINE_PATH=$GZ_SIM_PHYSICS_ENGINE_PATH:/usr/lib/x86_64-linux-gnu/gz-physics-7/engine-plugins/
gz sim -v4 -r <% if headless == 'true' %> -s <% end %> <%= world %>.sdf
<% elsif autopilot == 'ardupilot' %>
- gz_sim:
layout: main-vertical
panes:
- >
<% if camera == 'false' %>
sed -i '/<sensor/,/<\/sensor>/d' /aas/simulation_resources/aircraft_models/sensor_camera/model.sdf &&
<% end %>
<% if lidar == 'false' %>
sed -i '/<sensor/,/<\/sensor>/d' /aas/simulation_resources/aircraft_models/sensor_lidar/model.sdf &&
<% end %>
<% if autopilot == 'ardupilot' %>
/aas/simulation_resources/aircraft_models/_create_ardupilot_models.sh <%= num_quads %> <%= num_vtols %> &&
/aas/simulation_resources/simulation_worlds/_create_ardupilot_world.sh <%= num_quads %> <%= num_vtols %> /aas/simulation_resources/simulation_worlds/<%= world %>.sdf &&
GZ_SIM_SYSTEM_PLUGIN_PATH=/aas/github_apps/ardupilot_gazebo/build:$GZ_SIM_SYSTEM_PLUGIN_PATH
GZ_SIM_RESOURCE_PATH=/aas/simulation_resources/aircraft_models:/aas/simulation_resources/simulation_worlds:$GZ_SIM_RESOURCE_PATH
<% end %>
GZ_SIM_RESOURCE_PATH=$GZ_SIM_RESOURCE_PATH:/aas/simulation_resources/aircraft_models:/aas/simulation_resources/simulation_worlds
GZ_SIM_PHYSICS_ENGINE_PATH=$GZ_SIM_PHYSICS_ENGINE_PATH:/usr/lib/x86_64-linux-gnu/gz-physics-7/engine-plugins/
gz sim -v4 -r <% if headless == 'true' %> -s <% end %> populated_ardupilot.sdf
<% end %>
gz sim -v4 -r <% if headless == 'true' %> -s <% end %> <% if autopilot == 'px4' %> <%= world %>.sdf <% elsif autopilot == 'ardupilot' %> populated_ardupilot.sdf <% end %>
- >
(
PRIMARY_RES=$(xrandr | grep -oE '[0-9]+x[0-9]+' | head -1)
SCREEN_W=$(echo $PRIMARY_RES | cut -d'x' -f1)
SCREEN_H=$(echo $PRIMARY_RES | cut -d'x' -f2)
SCREEN_W=$(echo $PRIMARY_RES | cut -d'x' -f1); SCREEN_H=$(echo $PRIMARY_RES | cut -d'x' -f2)
SCREEN_SCALE=$((SCREEN_H * 100 / 1080)) # Full HD = 100%
WIN_W=$(( 800 * SCREEN_SCALE / 100 ))
WIN_H=$(( 600 * SCREEN_SCALE / 100 ))
POS_X=$((SCREEN_W - WIN_W))
POS_Y=$(( 0 ))
WIN_W=$(( 800 * SCREEN_SCALE / 100 )); WIN_H=$(( 600 * SCREEN_SCALE / 100 ))
POS_X=$((SCREEN_W - WIN_W)); POS_Y=$(( 0 ))
for i in {1..10}; do
sleep 2
if wmctrl -l | grep -q "Gazebo Sim"; then
Expand All @@ -68,90 +51,72 @@ windows:
done
)

<%
drones = []
num_quads.times { |i| drones << { type: 'quad', index: i } }
num_vtols.times { |i| drones << { type: 'vtol', index: i } }
%>

<% drones.each_with_index do |drone, drone_id| %>
<%
is_quad = drone[:type] == 'quad'
i = drone[:index]

if autopilot == 'px4'
autostart = is_quad ? 5140 : 5141
model_name = is_quad ? "x500_#{drone_id}" : "standard_vtol_#{drone_id}"
y_offset = is_quad ? i * 2 : 2 + i * 2
elsif autopilot == 'ardupilot'
vehicle_config = is_quad ? '-v ArduCopter -f gazebo-iris' : '-v ArduPlane'
model_name = is_quad ? "iris_with_ardupilot_#{drone_id + 1}" : "alti_transition_quad_#{drone_id + 1}"
sensor_path = is_quad ? 'model/iris/' : ''
end
%>
<% if autopilot == 'px4' %>
- px4_sitl_<%= drone_id + 1 %>:
<%
drones = []
num_quads.times { |i| drones << { type: 'quad', index: i } }
num_vtols.times { |i| drones << { type: 'vtol', index: i } }
%>
<% drones.each_with_index do |drone, sitl_instance| %>
<%
drone_id = sitl_instance + 1
is_quad = drone[:type] == 'quad'
if autopilot == 'px4'
autostart = is_quad ? 5140 : 5141
model_name = is_quad ? "x500_#{sitl_instance}" : "standard_vtol_#{sitl_instance}"
x_offset = drone[:index] * 2
y_offset = is_quad ? x_offset : x_offset + 2
sensor_path = ''
elsif autopilot == 'ardupilot'
vehicle_config = is_quad ? '-v ArduCopter -f gazebo-iris' : '-v ArduPlane'
model_name = is_quad ? "iris_with_ardupilot_#{drone_id}" : "alti_transition_quad_#{drone_id}"
sensor_path = is_quad ? 'model/iris/' : ''
end
%>
<% if autopilot == 'px4' %>
- px4_sitl_<%= drone_id %>:
layout: main-horizontal
panes:
- >
sleep <%= (drone_id + 1) * 3 %> &&
PX4_GZ_MODEL_POSE="<%= i * 2 %>,<%= y_offset %>,0.5,0,0,0"
PX4_SYS_AUTOSTART=<%= autostart %>
ROS_DOMAIN_ID=<%= drone_id + 1 %>
PX4_UXRCE_DDS_NS="Drone<%= drone_id + 1 %>"
PX4_UXRCE_DDS_AG_IP="<%= subnet_prefix %>.1.<%= drone_id + 1 %>"
PX4_UXRCE_DDS_PORT=8888
/aas/github_apps/PX4-Autopilot/build/px4_sitl_default/bin/px4 -i <%= drone_id %>
- "ROS_DOMAIN_ID=<%= drone_id + 1 %> ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock"
<% if lidar == 'true' %>
- "ROS_DOMAIN_ID=<%= drone_id + 1 %> ros2 run ros_gz_bridge parameter_bridge /world/<%= world %>/model/<%= model_name %>/model/simple_lidar/link/lidar/base_link/sensor/lidar3d/scan/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked --ros-args -r /world/<%= world %>/model/<%= model_name %>/model/simple_lidar/link/lidar/base_link/sensor/lidar3d/scan/points:=/lidar_points"
<% end %>
<% if camera == 'true' %>
- >
python3 /aas/simulation_resources/comms/gz_to_gst_image_bridge.py
--gz_topic /world/<%= world %>/model/<%= model_name %>/model/simple_camera/link/mono_cam/base_link/sensor/imager/image
--ip <%= subnet_prefix %>.1.<%= drone_id + 1 %> --port 5600
<% end %>
<% elsif autopilot == 'ardupilot' %>
- ardupilot_sitl_<%= drone_id + 1 %>:
sleep <%= drone_id * 3 %> &&
PX4_GZ_MODEL_POSE="<%= x_offset %>,<%= y_offset %>,0.5,0,0,0"
PX4_SYS_AUTOSTART=<%= autostart %> ROS_DOMAIN_ID=<%= drone_id %>
PX4_UXRCE_DDS_NS="Drone<%= drone_id %>" PX4_UXRCE_DDS_AG_IP="<%= subnet_prefix %>.1.<%= drone_id %>" PX4_UXRCE_DDS_PORT=8888
/aas/github_apps/PX4-Autopilot/build/px4_sitl_default/bin/px4 -i <%= sitl_instance %>
<% elsif autopilot == 'ardupilot' %>
- ardupilot_sitl_<%= drone_id %>:
layout: main-horizontal
panes:
- >
sleep <%= (drone_id + 1) * 3 %> &&
mkdir -p /aas/ardu_sitl_<%= drone_id + 1 %> && cd /aas/ardu_sitl_<%= drone_id + 1 %> &&
sleep <%= drone_id * 5 %> && mkdir -p /aas/ardu_sitl_<%= drone_id %> && cd /aas/ardu_sitl_<%= drone_id %> &&
/aas/github_apps/ardupilot/Tools/autotest/sim_vehicle.py
<%= vehicle_config %>
--model JSON
-I <%= drone_id %>
--sysid <%= drone_id + 1 %>
-l $(awk -F "[><]" "/<spherical_coordinates>/,/<\/spherical_coordinates>/" /aas/simulation_resources/simulation_worlds/<%= world %>.sdf | awk -F "[><]" "/latitude_deg/ {print \$3}"),$(awk -F "[><]" "/<spherical_coordinates>/,/<\/spherical_coordinates>/" /aas/simulation_resources/simulation_worlds/<%= world %>.sdf | awk -F "[><]" "/longitude_deg/ {print \$3}"),$(awk -F "[><]" "/<spherical_coordinates>/,/<\/spherical_coordinates>/" /aas/simulation_resources/simulation_worlds/<%= world %>.sdf | awk -F "[><]" "/elevation/ {print \$3}"),0
--out=udp:127.0.0.1:<%= 21550 + drone_id %>
--out=udp:<%= subnet_prefix %>.1.<%= drone_id + 1 %>:<%= 22530 + drone_id %>
<%= vehicle_config %> --model JSON
-I <%= sitl_instance %> --sysid <%= drone_id %>
--add-param-file=/aas/simulation_resources/aircraft_models/<%= model_name %>/ardupilot-4.6.params
- "ROS_DOMAIN_ID=<%= drone_id + 1 %> ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock"
- mavproxy.py --state-basedir=/aas/ardu_sitl_<%= drone_id + 1 %>/mavproxy --master=udp:127.0.0.1:<%= 21550 + drone_id %> --out=udp:127.0.0.1:<%= 14550 + drone_id %> --out=udp:127.0.0.1:<%= 14540 + drone_id %>
-l $(awk -F "[><]" "/<spherical_coordinates>/,/<\/spherical_coordinates>/" /aas/simulation_resources/simulation_worlds/<%= world %>.sdf | awk -F "[><]" "/latitude_deg/ {print \$3}"),$(awk -F "[><]" "/<spherical_coordinates>/,/<\/spherical_coordinates>/" /aas/simulation_resources/simulation_worlds/<%= world %>.sdf | awk -F "[><]" "/longitude_deg/ {print \$3}"),$(awk -F "[><]" "/<spherical_coordinates>/,/<\/spherical_coordinates>/" /aas/simulation_resources/simulation_worlds/<%= world %>.sdf | awk -F "[><]" "/elevation/ {print \$3}"),0
--out=udp:<%= subnet_prefix %>.1.<%= drone_id %>:8888
--out=udp:127.0.0.1:<%= 14540 + sitl_instance %> --out=udp:127.0.0.1:<%= 14550 + sitl_instance %>
<% if is_quad %>
- sleep <%= drone_id * 5 + 35 %> && tmux send-keys -t 'sim:ardupilot_sitl_<%= drone_id %>.0' 'rc 3 1500' C-m
<% end %>
<% end %>
- "ROS_DOMAIN_ID=<%= drone_id %> ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock"
<% if lidar == 'true' %>
- "ROS_DOMAIN_ID=<%= drone_id + 1 %> ros2 run ros_gz_bridge parameter_bridge /world/<%= world %>/model/<%= model_name %>/<%= sensor_path %>model/simple_lidar/link/lidar/base_link/sensor/lidar3d/scan/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked --ros-args -r /world/<%= world %>/model/<%= model_name %>/<%= sensor_path %>model/simple_lidar/link/lidar/base_link/sensor/lidar3d/scan/points:=/lidar_points"
- "ROS_DOMAIN_ID=<%= drone_id %> ros2 run ros_gz_bridge parameter_bridge /world/<%= world %>/model/<%= model_name %>/<%= sensor_path %>model/simple_lidar/link/lidar/base_link/sensor/lidar3d/scan/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked --ros-args -r /world/<%= world %>/model/<%= model_name %>/<%= sensor_path %>model/simple_lidar/link/lidar/base_link/sensor/lidar3d/scan/points:=/lidar_points"
<% end %>
<% if camera == 'true' %>
- >
sleep <%= drone_id * 3 %> &&
python3 /aas/simulation_resources/comms/gz_to_gst_image_bridge.py
--gz_topic /world/<%= world %>/model/<%= model_name %>/<%= sensor_path %>model/simple_camera/link/mono_cam/base_link/sensor/imager/image
--ip <%= subnet_prefix %>.1.<%= drone_id + 1 %> --port 5600
--ip <%= subnet_prefix %>.1.<%= drone_id %> --port 5600
<% end %>
<% if is_quad %>
- >
sleep <%= (drone_id + 1) * 3 + 35 %> &&
tmux send-keys -t 'sim:ardupilot_sitl_<%= drone_id + 1 %>.0' 'rc 3 1500' C-m
<% end %>
<% end %>
<% end %>
<% end %>

- ground_system_over_zenoh:
layout: even-vertical
panes:
- "ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock"
- sleep 3 && ros2 run ground_system oracle --num-drones <%= num_quads + num_vtols %> --base-port 14540 --rate 1.0 <% if simulated_time == 'true' %> --ros-args -p use_sim_time:=True<% end %>
- ros2 run ground_system oracle --num-drones <%= num_quads + num_vtols %> --ip 127.0.0.1 --base-port 14540 --rate 1.0 <% if simulated_time == 'true' %> --ros-args -p use_sim_time:=True<% end %>
- zenoh-bridge-ros2dds -c /aas/simulation_resources/comms/zenoh_config_ground.json5

- qgc:
Expand All @@ -167,13 +132,10 @@ windows:
gosu qgcuser /squashfs-root/AppRun &
(
PRIMARY_RES=$(xrandr | grep -oE '[0-9]+x[0-9]+' | head -1)
SCREEN_W=$(echo $PRIMARY_RES | cut -d'x' -f1)
SCREEN_H=$(echo $PRIMARY_RES | cut -d'x' -f2)
SCREEN_W=$(echo $PRIMARY_RES | cut -d'x' -f1); SCREEN_H=$(echo $PRIMARY_RES | cut -d'x' -f2)
SCREEN_SCALE=$((SCREEN_H * 100 / 1080)) # Full HD = 100%
WIN_W=$(( 800 * SCREEN_SCALE / 100 ))
WIN_H=$(( 600 * SCREEN_SCALE / 100 ))
POS_X=$((SCREEN_W - WIN_W))
POS_Y=$((WIN_H))
WIN_W=$(( 800 * SCREEN_SCALE / 100 )); WIN_H=$(( 600 * SCREEN_SCALE / 100 ))
POS_X=$((SCREEN_W - WIN_W)); POS_Y=$((WIN_H))
for i in {1..10}; do
sleep 2
if wmctrl -l | grep -q "QGroundControl"; then
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
from ground_system_msgs.msg import SwarmObs, DroneObs

class OracleNode(Node):
def __init__(self, num_drones, base_port, publish_rate):
def __init__(self, num_drones, ip, base_port, publish_rate):
super().__init__('oracle')

self.drone_obs = {} # Thread-safe storage for latest data
Expand All @@ -20,7 +20,7 @@ def __init__(self, num_drones, base_port, publish_rate):
for i in range(num_drones):
drone_id = i + 1
port = base_port + i
connection_string = f"udp:127.0.0.1:{port}"
connection_string = f"udp:{ip}:{port}"
thread = threading.Thread(target=self.mavlink_listener, args=(drone_id, connection_string))
thread.daemon = True
thread.start()
Expand Down Expand Up @@ -91,6 +91,7 @@ def add_noise(self, value, std_dev):
def main(args=None):
parser = argparse.ArgumentParser(description='Oracle Node')
parser.add_argument('--num-drones', type=int, required=True, help='Number of drones to listen for.')
parser.add_argument('--ip', type=str, default='127.0.0.1', help='IP address to listen on.')
parser.add_argument('--base-port', type=int, default=14540, help='Base UDP port to start listening from.')
parser.add_argument('--rate', type=float, default=10.0, help='Publishing rate in Hz.')

Expand All @@ -100,6 +101,7 @@ def main(args=None):

node = OracleNode(
num_drones=cli_args.num_drones,
ip=cli_args.ip,
base_port=cli_args.base_port,
publish_rate=cli_args.rate
)
Expand Down
2 changes: 1 addition & 1 deletion supplementary/REQUIREMENTS_WSL.md
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ From PowerShell
wsl ~

sudo apt update && sudo apt install -y mesa-utils
nvidia-smi # From WSL, check NVIDIA driver (these instructions are tested on Driver Version: 581.15, CUDA Version:13.0)
nvidia-smi # From WSL, check NVIDIA driver (these instructions are tested on Driver Version: 581.42, CUDA Version:13.0)
glxinfo -B # Check the GPU is the OpenGL renderer
```

Expand Down
2 changes: 1 addition & 1 deletion supplementary/SETUP_AVIONICS.md
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ sudo /opt/nvidia/jetson-io/jetson-io.py

sudo dmesg | grep -i imx219 # After reboot, this will show at least one imx219 successfully bound

# Inspect camera resolution and frame rate
# Inspect device (e.g. /dev/video0) resolution and frame rate
sudo apt update && sudo apt install -y v4l-utils
v4l2-ctl --list-formats-ext -d /dev/video0
```
Expand Down