Drivers onboard f1tenth race cars. This branch is under development for migration to ROS2. See the documentation of F1TENTH on how to get started.
-
Install Navigation2
sudo apt install ros-<ros2_distro>-navigation2 ros-<distro>-nav2-bringup
-
Install SLAM Toolbox
sudo apt install ros-<ros2-distro>-slam-toolbox
-
Install Joint State Publisher
sudo apt install ros-<ros2-distro>-joint-state-publisher
-
Install Robot Localization
sudo apt install ros-<ros2-distro>-robot-localization
On Sony Interactive Entertainment Wireless Controller, the LB button is the deadman's switch for teleop, and the RB button is the deadman's switch for navigation. You can also remap buttons. See how on the readthedocs documentation.
/drive
: Topic for autonomous navigation, usesAckermannDriveStamped
messages.
/scan
: Topic forLaserScan
messages./odom
: Topic forOdometry
messages./sensors/imu/raw
: Topic forImu
messages./sensors/core
: Topic for telemetry data from the VESC
- ackermann_msgs https://index.ros.org/r/ackermann_msgs/#humble.
- sllidar_node https://github.com/Slamtec/sllidar_ros2/tree/humble This is the driver for SLAMTEC LiDARs.
- joy https://index.ros.org/p/joy/#humble. This is the driver for joysticks in ROS 2.
- teleop_tools https://index.ros.org/p/teleop_tools/#humble. This is the package for teleop with joysticks in ROS 2.
- vesc https://github.com/RISE-Dependable-Transport-Systems/vesc/tree/humble. This is the driver for VESCs in ROS 2.
- ackermann_mux GitHub - f1tenth/ackermann_mux: Twist multiplexer. This is a package for multiplexing ackermann messages in ROS 2.
- slam_toolbox https://github.com/SteveMacenski/slam_toolbox/tree/humble. This is a package for SLAM.
- nav2 https://github.com/ros-planning/navigation2/tree/humble. This is a ROS 2 navigation library.
- joint_state_publisher https://index.ros.org/p/joint_state_publisher/#humble. Package for publishing sensor_msgs/msg/JointState messages for a robot described with URDF.
- robot_localization https://index.ros.org/p/robot_localization/#humble. Package of nonlinear state estimation nodes.
f1tenth_stack
: maintains the bringup launch and all parameter filesdts_stack
: maintains control station launch and rover launch, URDF file, all parameter files and a node to convert twist messages to ackermann messages.
- ros2 launch dts_stack gazebo_rviz.launch.py frame_prefix:=robot/ use_sim_time:=true
- ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=/home/ubuntu/src/f1tenth_ws/src/f1tenth_system/dts_stack/config/ros_gazebo_bridges.yaml
- ros2 run teleop_twist_keyboard teleop_twist_keyboard
- or use joypad
- In rviz, set TF prefix to robot and fixed frame to robot/odom
- joy_teleop
- ackermann_to_vesc_node
- vesc_to_odom_node
- vesc_driver_node
- ackermann_mux
- sllidar_node
- robot_state_publisher
- joint_state_publisher
- rviz2
- ekf_filter_node
- twist_to_ackermann
- nav2_controller
- nav2_planner
- nav2_recoveries
- nav2_bt_navigator
- nav2_waypoint_follower
- nav2_lifecycle_manager
- slam_toolbox
- Publishes to:
- drive
- Subscribes to:
- cmd_vel
- Publishes to:
- map
- Subscribes to:
- scan
- Parameters:
- duty_cycle_min, duty_cycle_max
- current_min, current_max
- brake_min, brake_max
- speed_min, speed_max
- position_min, position_max
- servo_min, servo_max
- Publishes to:
- sensors/core
- sensors/servo_position_command
- sensors/imu
- sensors/imu/raw
- Subscribes to:
- commands/motor/duty_cycle
- commands/motor/current
- commands/motor/brake
- commands/motor/speed
- commands/motor/position
- commands/servo/position
- Parameters:
- speed_to_erpm_gain
- speed_to_erpm_offset
- steering_angle_to_servo_gain
- steering_angle_to_servo_offset
- Publishes to:
- ackermann_cmd
- Subscribes to:
- commands/motor/speed
- commands/servo/position
- Parameters:
- odom_frame
- base_frame
- use_servo_cmd_to_calc_angular_velocity
- speed_to_erpm_gain
- speed_to_erpm_offset
- steering_angle_to_servo_gain
- steering_angle_to_servo_offset
- wheelbase
- publish_tf
- Publishes to:
- odom
- Subscribes to:
- sensors/core
- sensors/servo_position_command
- Parameters:
- rpm_input_topic
- rpm_output_topic
- servo_input_topic
- servo_output_topic
- max_acceleration
- speed_max
- speed_min
- throttle_smoother_rate
- speed_to_erpm_gain
- max_servo_speed
- steering_angle_to_servo_gain
- servo_smoother_rate
- servo_max
- servo_min
- steering_angle_to_servo_offset
- Publishes to:
- topic described in rpm_output_topic
- topic described in servo_output_topic
- Subscribes to:
- topic described in rpm_input_topic
- topic described in servo_input_topic