Skip to content
Open
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
28 changes: 27 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,30 @@
# f1tenth_system
![image](https://github.com/user-attachments/assets/df4ae9c0-bf45-48c3-923c-35cd488ebeab)# How to run car (capstone instructions):
1. create local hotspot: on laptop go to Settings/Wifi then click the three dots in the upper right hand corner and click 'Turn on wifi hotspot'
2. plug in and connect jetson to the monitor and join the hotspot (f1net). run the command line 'hostname -I' on the jetson to find the new IP address.
3. (optional) to access code on the jetson without a monitor: ssh into the jetson using VScode on the laptop. on VScode press f1, then click 'SSH: Connect to host', type in f1jetson@my-jetson or f1jetson@ip_address (e.g. [email protected])
4. ssh into jetson on the laptop in command window (ssh f1jetson@my-jetson). note: the source /opt/ros/foxy/setup.bash and source ~/f1tenth_ws/install/setup.bash are added to the .bashrc file so no need to run those commnads.
5. To launch the system, on jetson terminal: ros2 launch f1tenth_stack bringup_launch.py
6. on laptop terminal: ros2 run joy joy_node.
a. to move car: hold lb (top left button, the 'dead man' switch) at all times. use the left stick to go forwards/backwards and the right stick to steer left/right. its clunky.
8. to launch rviz: on laptop terminal rune: rviz2.
a. to add LiDAR point cloud: click add (bottom left corner), then click LaserScan. Expand LaserScan. In the topic box write /scan. under globaloptions/fixed frame change it laser. its useful to increase the size of to 0.03 (under LaserScan/Size (m)).
9. to run SLAM:
a. on laptop terminal run: runslam (this is an alias/short cut for a longer command line, view bashrc file to see the full command line e.g. ros2 launch slam_toolbox online_async_launch.py params_file...)
b. on Rviz: unclick LaserScan. Add Map (botton left corner), under topic select /map. under fixed frame click map. it looks slightly nice if you click the Type drop down menu under Views (right panel), then click TopDownOrtho.
c. to save map: on laptop terminal: ros2 launch nav2_map_server map_saver_server.launch.py,
then run: ros2 run nav2_map_server map_saver_cli -f /home/capstone/f1host_ws/src/f1tenth_stack/map/_map_name_
d. to clean up map: click/look up GNU Image Manipulation Program, then find the map in the workspace, right click the paintbrush to select pencil (for hard edges), and color picker to select grey or black colours.



ros2 run nav2_map_server --ros-args -p yaml_filename:=test303.yaml -p use_sim_time:=false
ros2 run nav2_util lifecycle_bringup map_server

ros2 run nav2_amcl amcl --ros-args -p base_frame_id:=base_link use_sim_time:=false
ros2 run nav2_util lifecycle_bringup amcl


# From original source: f1tenth_system

Drivers onboard f1tenth race cars. This branch is under development for migration to ROS2. See the [documentation of F1TENTH](https://f1tenth.readthedocs.io/en/foxy_test/getting_started/firmware/index.html) on how to get started.

Expand Down
2 changes: 1 addition & 1 deletion ackermann_mux
75 changes: 75 additions & 0 deletions description/ego_racecar.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="racecar">

<xacro:property name="wheelbase" value="0.3302" />
<xacro:property name="width" value="0.2032" />
<xacro:property name="height" value="0.1" />
<xacro:property name="ground_offset" value="0.04" />
<xacro:property name="wheel_radius" value="0.0508" />
<xacro:property name="wheel_length" value="0.0381" />
<xacro:property name="laser_distance_from_base_link" value="0.275" />
<xacro:property name="laser_height" value="0.05" />
<xacro:property name="laser_radius" value="0.026" />
<xacro:property name="car_name" value="ego_racecar" />

<material name="black">
<color rgba="0.2 0.2 0.2 1."/>
</material>

<material name="blue">
<color rgba="0.3 0.57 1. 1."/>
</material>

<!-- Base Link -->
<link name="base_link">
<visual>
<origin xyz="${wheelbase/2} 0 ${ground_offset+height/2}"/>
<geometry>
<box size="${wheelbase} ${width} ${height}"/>
</geometry>
<material name="blue"/>
</visual>
</link>

<!-- Odometry Frame -->
<joint name="odom_to_base" type="floating">
<parent link="odom"/>
<child link="base_link"/>
</joint>

<link name="odom"/>

<!-- LiDAR Sensor -->
<joint name="base_to_laser" type="fixed">
<parent link="base_link"/>
<child link="lidar_link"/>
<origin xyz="${laser_distance_from_base_link} 0 ${ground_offset+height+(laser_height/2)}"/>
</joint>

<link name="lidar_link">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_height}"/>
</geometry>
<material name="black"/>
</visual>
</link>

<!-- Wheels -->
<joint name="base_to_back_left_wheel" type="fixed">
<parent link="base_link"/>
<child link="back_left_wheel"/>
<origin xyz="0 ${(wheel_length+width)/2} ${wheel_radius}"/>
</joint>

<link name="back_left_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>

</robot>
129 changes: 129 additions & 0 deletions description/ego_racecarORIGINAL.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
<?xml version="1.0"?>

<!-- A simple model of the racecar for rviz -->

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="racecar">

<xacro:property name="wheelbase" value="0.3302" />
<xacro:property name="width" value="0.2032" />
<xacro:property name="height" value="0.1" />
<xacro:property name="ground_offset" value="0.04" />
<xacro:property name="wheel_radius" value="0.0508" />
<xacro:property name="wheel_length" value="0.0381" />
<xacro:property name="laser_distance_from_base_link" value="0.275" />
<xacro:property name="laser_height" value="0.05" />
<xacro:property name="laser_radius" value="0.026" />
<xacro:property name="car_name" value="ego_racecar" />

<material name="black">
<color rgba="0.2 0.2 0.2 1."/>
</material>

<material name="blue">
<color rgba="0.3 0.57 1. 1."/>
</material>

<link name="${car_name}/base_link">
<visual>
<origin xyz="${wheelbase/2} 0 ${ground_offset+height/2}"/>
<geometry>
<box size="${wheelbase} ${width} ${height}"/>
</geometry>
<material name="blue"/>
</visual>
</link>

<joint name="base_to_laser_model" type="fixed">
<parent link="${car_name}/base_link"/>
<child link="${car_name}/laser_model"/>
<origin xyz="${laser_distance_from_base_link} 0 ${ground_offset+height+(laser_height/2)}"/>
</joint>

<link name="${car_name}/laser_model">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_height}"/>
</geometry>
<material name="black"/>
</visual>
</link>

<joint name="$base_to_back_left_wheel" type="fixed">
<parent link="${car_name}/base_link"/>
<child link="${car_name}/back_left_wheel"/>
<origin xyz="0 ${(wheel_length+width)/2} ${wheel_radius}"/>
</joint>

<link name="${car_name}/back_left_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>

<joint name="base_to_back_right_wheel" type="fixed">
<parent link="${car_name}/base_link"/>
<child link="${car_name}/back_right_wheel"/>
<origin xyz="0 ${-(wheel_length+width)/2} ${wheel_radius}"/>
</joint>

<link name="${car_name}/back_right_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>

<joint name="base_to_front_left_hinge" type="fixed">
<parent link="${car_name}/base_link"/>
<child link="${car_name}/front_left_hinge"/>
<origin xyz="${wheelbase} ${(wheel_length+width)/2} ${wheel_radius}"/>
</joint>

<link name="${car_name}/front_left_hinge"/>

<joint name="front_left_hinge_to_wheel" type="continuous">
<parent link="${car_name}/front_left_hinge"/>
<child link="${car_name}/front_left_wheel"/>
</joint>

<link name="${car_name}/front_left_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>

<joint name="base_to_front_right_hinge" type="fixed">
<parent link="${car_name}/base_link"/>
<child link="${car_name}/front_right_hinge"/>
<origin xyz="${wheelbase} ${-(wheel_length+width)/2} ${wheel_radius}"/>
</joint>

<link name="${car_name}/front_right_hinge"/>

<joint name="front_right_hinge_to_wheel" type="continuous">
<parent link="${car_name}/front_right_hinge"/>
<child link="${car_name}/front_right_wheel"/>
</joint>

<link name="${car_name}/front_right_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>

</robot>
11 changes: 6 additions & 5 deletions f1tenth_stack/config/f1tenth_online_async.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@ slam_toolbox:
# ROS Parameters
odom_frame: odom
map_frame: map
base_frame: laser
# base_frame: laser
base_frame: base_link #?
scan_topic: /scan
mode: mapping #localization

Expand All @@ -27,8 +28,8 @@ slam_toolbox:
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
max_laser_range: 20.0 #for rastering images
resolution: 0.05 #// CONFIGURABLE
max_laser_range: 16.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 1.0
tf_buffer_duration: 30.
Expand All @@ -38,8 +39,8 @@ slam_toolbox:
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.5
minimum_travel_heading: 0.5
minimum_travel_distance: 0.1 #0.5
minimum_travel_heading: 0.1 #0.5
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
link_match_minimum_response_fine: 0.1
Expand Down
6 changes: 4 additions & 2 deletions f1tenth_stack/config/joy_teleop.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
joy:
joy_node: #joy
ros__parameters:
# device_name: /dev/input/joypad-f710
device_name: /dev/input/joypad-f310
# device_name: /dev/input/js0
device_id: 0
deadzone: 0.01
autorepeat_rate: 20.0
Expand Down Expand Up @@ -30,7 +32,7 @@ joy_teleop:
axis_mappings:
drive-speed:
axis: 1
scale: 5.0
scale: 1.0
offset: 0.0
drive-steering_angle:
axis: 2
Expand Down
74 changes: 74 additions & 0 deletions f1tenth_stack/config/localisation_online_async.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
slam_toolbox:
ros__parameters:

# Plugin params
solver_plugin: solver_plugins::CeresSolver
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_loss_function: None

# ROS Parameters
odom_frame: odom
map_frame: map
# base_frame: laser
base_frame: base_link #?
scan_topic: /scan
mode: localization

# if you'd like to immediately start continuing a map at a given pose
# or at the dock, but they are mutually exclusive, if pose is given
# will use pose
map_file_name: /home/f1jetson/f1tenth_ws/src/f1tenth_system/f1tenth_stack/maps/map_6
# map_start_pose: [0.0, 0.0, 0.0]
map_start_at_dock: true

debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
max_laser_range: 16.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 1.0
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
enable_interactive_mode: true

# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.1 #0.5
minimum_travel_heading: 0.1 #0.5
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.5
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1

# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03

# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0

fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true
Loading