diff --git a/ROS Workspace/autodrive/config/common_costmap_params.yaml b/ROS Workspace/autodrive/config/common_costmap_params.yaml index 3014d54..adf90df 100644 --- a/ROS Workspace/autodrive/config/common_costmap_params.yaml +++ b/ROS Workspace/autodrive/config/common_costmap_params.yaml @@ -1,18 +1,20 @@ -footprint: [ [-0.1,-0.125], [0.5,-0.125], [0.5,0.125], [-0.1,0.125] ] -transform_tolerance: 0.2 +footprint: [ [-0.25,-0.135], [0.25,-0.135], [0.25,0.135], [-0.25,0.135] ] +# car length = 0.50 car width = 0.27 +# wheel base = 0.33 track width = 0.23 +# front offset = 0.09 rear offset = 0.08 +transform_tolerance: 1 obstacle_layer: enabled: true obstacle_range: 3.0 raytrace_range: 3.5 - inflation_radius: 0.2 track_unknown_space: false combination_method: 1 observation_sources: lidar - lidar: {sensor_frame: lidar, data_type: LaserScan, topic: scan, marking: true, clearing: true} + lidar: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true} inflation_layer: enabled: true cost_scaling_factor: 10.0 # exponential rate at which the obstacle cost drops off (default: 10) - inflation_radius: 0.025 # max. distance from an obstacle at which costs are incurred for planning paths + inflation_radius: 0.15 # m (max. distance from an obstacle at which costs are incurred for planning paths) static_layer: enabled: true map_topic: "/map" diff --git a/ROS Workspace/autodrive/config/global_costmap_params.yaml b/ROS Workspace/autodrive/config/global_costmap_params.yaml index 59e579d..89e9d25 100644 --- a/ROS Workspace/autodrive/config/global_costmap_params.yaml +++ b/ROS Workspace/autodrive/config/global_costmap_params.yaml @@ -1,7 +1,7 @@ global_costmap: global_frame: map - robot_base_frame: nigel - update_frequency: 2.0 + robot_base_frame: base_link + update_frequency: 5.0 publish_frequency: 5.0 transform_tolerance: 30 width: 80 diff --git a/ROS Workspace/autodrive/config/local_costmap_params.yaml b/ROS Workspace/autodrive/config/local_costmap_params.yaml index 419c4c3..4dfa90f 100644 --- a/ROS Workspace/autodrive/config/local_costmap_params.yaml +++ b/ROS Workspace/autodrive/config/local_costmap_params.yaml @@ -1,11 +1,11 @@ local_costmap: global_frame: odom - robot_base_frame: nigel - update_frequency: 2.0 + robot_base_frame: base_link + update_frequency: 5.0 publish_frequency: 5.0 rolling_window: true - width: 1.5 - height: 1.5 + width: 3.0 # m + height: 3.0 # m resolution: 0.05 transform_tolerance: 10 plugins: diff --git a/ROS Workspace/autodrive/config/planner_params.yaml b/ROS Workspace/autodrive/config/planner_params.yaml index e00e79c..0412260 100644 --- a/ROS Workspace/autodrive/config/planner_params.yaml +++ b/ROS Workspace/autodrive/config/planner_params.yaml @@ -17,22 +17,25 @@ TebLocalPlannerROS: feasibility_check_no_poses: 2 allow_init_backward_motion: false # Robot - max_vel_x: 0.2 # [sim max: 0.26 m/s] - max_vel_x_backwards: 0.2 # [sim max: 0.23 m/s] - max_vel_theta: 0.5236 # [sim max: 0.67 rad/s] angular velocity is also bounded by min_turning_radius in case of a carlike robot (omega = v/r) + # car length = 0.50 car width = 0.27 + # wheel base = 0.33 track width = 0.23 + # front offset = 0.09 rear offset = 0.08 + max_vel_x: 0.4 # m/s + max_vel_x_backwards: 0.2 # m/s + max_vel_theta: 0.2 # rad/s [angular velocity is also bounded by min_turning_radius in case of a carlike robot (omega = v/r)] acc_lim_x: 0.15 acc_lim_theta: 0.3927 # Carlike robot parameters - min_turning_radius: 0.24515 # min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually) - wheelbase: 0.14154 # wheelbase of the carlike robot + min_turning_radius: 0.74 # min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually) + wheelbase: 0.33 # wheelbase of the carlike robot cmd_angle_instead_rotvel: True # return steering angle instead of the rotvel (angular.z of twist message) footprint_model: type: "line" - line_start: [-0.07077, 0.0] # for type "line" - line_end: [0.07077, 0.0] # for type "line" + line_start: [-0.18, 0.0] # for type "line" + line_end: [0.17, 0.0] # for type "line" # GoalTolerance - xy_goal_tolerance: 0.1 - yaw_goal_tolerance: 0.1 + xy_goal_tolerance: 0.1 # m + yaw_goal_tolerance: 0.4 # rad free_goal_vel: False # Obstacles min_obstacle_dist: 0.2 # this value must also include our robot's expansion, since footprint_model is set to "line". @@ -53,14 +56,14 @@ TebLocalPlannerROS: weight_acc_lim_x: 1 weight_acc_lim_theta: 1 weight_kinematics_nh: 1000 - weight_kinematics_forward_drive: 100 + weight_kinematics_forward_drive: 1000 weight_kinematics_turning_radius: 1 weight_optimaltime: 1 weight_obstacle: 50 weight_dynamic_obstacle: 10 # Homotopy Class Planner - enable_homotopy_class_planning: True - enable_multithreading: True + enable_homotopy_class_planning: False + enable_multithreading: False simple_exploration: False max_number_classes: 4 selection_cost_hysteresis: 1.0 diff --git a/ROS Workspace/autodrive/launch/testbed_amcl.launch b/ROS Workspace/autodrive/launch/testbed_amcl.launch index f9cc284..2d98bce 100644 --- a/ROS Workspace/autodrive/launch/testbed_amcl.launch +++ b/ROS Workspace/autodrive/launch/testbed_amcl.launch @@ -27,7 +27,7 @@ # topic where the lidar scans are being published # topic where to publish the odometry estimations - # wheter or not to publish the tf::transform (base_frame->odom_frame) + # whether or not to publish the tf::transform (base_frame->odom_frame) # frame_id (tf) of the mobile base # frame_id (tf) to publish the odometry estimations # leave empty to start at point (0,0) diff --git a/ROS Workspace/autodrive/launch/testbed_amcl_remote.launch b/ROS Workspace/autodrive/launch/testbed_amcl_remote.launch index da3bafe..d2addfb 100644 --- a/ROS Workspace/autodrive/launch/testbed_amcl_remote.launch +++ b/ROS Workspace/autodrive/launch/testbed_amcl_remote.launch @@ -18,7 +18,7 @@ # topic where the lidar scans are being published # topic where to publish the odometry estimations - # wheter or not to publish the tf::transform (base_frame->odom_frame) + # whether or not to publish the tf::transform (base_frame->odom_frame) # frame_id (tf) of the mobile base # frame_id (tf) to publish the odometry estimations # leave empty to start at point (0,0) diff --git a/ROS Workspace/autodrive/launch/testbed_lidar_odometry.launch b/ROS Workspace/autodrive/launch/testbed_lidar_odometry.launch index 2646102..94d3c47 100644 --- a/ROS Workspace/autodrive/launch/testbed_lidar_odometry.launch +++ b/ROS Workspace/autodrive/launch/testbed_lidar_odometry.launch @@ -21,7 +21,7 @@ # topic where the lidar scans are being published # topic where to publish the odometry estimations - # wheter or not to publish the tf::transform (base_frame->odom_frame) + # whether or not to publish the tf::transform (base_frame->odom_frame) # frame_id (tf) of the mobile base # frame_id (tf) to publish the odometry estimations # leave empty to start at point (0,0) diff --git a/ROS Workspace/autodrive/launch/testbed_lidar_odometry_remote.launch b/ROS Workspace/autodrive/launch/testbed_lidar_odometry_remote.launch index fe26e9b..ea918f0 100644 --- a/ROS Workspace/autodrive/launch/testbed_lidar_odometry_remote.launch +++ b/ROS Workspace/autodrive/launch/testbed_lidar_odometry_remote.launch @@ -12,7 +12,7 @@ # topic where the lidar scans are being published # topic where to publish the odometry estimations - # wheter or not to publish the tf::transform (base_frame->odom_frame) + # whether or not to publish the tf::transform (base_frame->odom_frame) # frame_id (tf) of the mobile base # frame_id (tf) to publish the odometry estimations # leave empty to start at point (0,0) diff --git a/ROS Workspace/autodrive/launch/testbed_navigation.launch b/ROS Workspace/autodrive/launch/testbed_navigation.launch index bdbd1cc..f40e917 100644 --- a/ROS Workspace/autodrive/launch/testbed_navigation.launch +++ b/ROS Workspace/autodrive/launch/testbed_navigation.launch @@ -26,7 +26,7 @@ # topic where the lidar scans are being published # topic where to publish the odometry estimations - # wheter or not to publish the tf::transform (base_frame->odom_frame) + # whether or not to publish the tf::transform (base_frame->odom_frame) # frame_id (tf) of the mobile base # frame_id (tf) to publish the odometry estimations # leave empty to start at point (0,0) diff --git a/ROS Workspace/autodrive/launch/testbed_navigation_remote.launch b/ROS Workspace/autodrive/launch/testbed_navigation_remote.launch index 6276940..c6aec3c 100644 --- a/ROS Workspace/autodrive/launch/testbed_navigation_remote.launch +++ b/ROS Workspace/autodrive/launch/testbed_navigation_remote.launch @@ -17,7 +17,7 @@ # topic where the lidar scans are being published # topic where to publish the odometry estimations - # wheter or not to publish the tf::transform (base_frame->odom_frame) + # whether or not to publish the tf::transform (base_frame->odom_frame) # frame_id (tf) of the mobile base # frame_id (tf) to publish the odometry estimations # leave empty to start at point (0,0) diff --git a/ROS Workspace/autodrive/scripts/nav_ctrl.py b/ROS Workspace/autodrive/scripts/nav_ctrl.py index 75b8f89..87428e7 100644 --- a/ROS Workspace/autodrive/scripts/nav_ctrl.py +++ b/ROS Workspace/autodrive/scripts/nav_ctrl.py @@ -2,14 +2,14 @@ import rospy from geometry_msgs.msg import Twist -from std_msgs.msg import Float32 +from ackermann_msgs.msg import AckermannDriveStamped ################################################################################ DRIVE_LIMIT = 1 STEER_LIMIT = 1 -THROTTLE_CONST = 1/0.26 -STEERING_CONST = -1/0.5236 +THROTTLE_CONST = 4 +STEERING_CONST = 1 def constrain(input, low, high): if input < low: @@ -30,15 +30,19 @@ def boundDrive(drive_cmd): ################################################################################ -steer_pub = rospy.Publisher('steer_cmd', Float32, queue_size=10) -drive_pub = rospy.Publisher('drive_cmd', Float32, queue_size=10) +control_pub = rospy.Publisher('/vesc/low_level/ackermann_cmd_mux/input/teleop', AckermannDriveStamped, queue_size=10) +control_msg = AckermannDriveStamped() def navCtrlCallback(data): global throttle, steering - throttle = boundDrive(0.2 + (THROTTLE_CONST * data.linear.x)) + throttle = boundDrive(THROTTLE_CONST * data.linear.x) steering = boundSteer(STEERING_CONST * data.angular.z) - drive_pub.publish(Float32(throttle)) - steer_pub.publish(Float32(steering)) + + control_msg.header.stamp = rospy.Time.now() + control_msg.header.frame_id = 'base_link' + control_msg.drive.speed = throttle + control_msg.drive.steering_angle = steering + control_pub.publish(control_msg) ################################################################################ diff --git a/ROS Workspace/autodrive/scripts/teleop.py b/ROS Workspace/autodrive/scripts/teleop.py index 76a0974..b10e973 100644 --- a/ROS Workspace/autodrive/scripts/teleop.py +++ b/ROS Workspace/autodrive/scripts/teleop.py @@ -1,7 +1,37 @@ #!/usr/bin/env python +''' +BSD 2-Clause License + +Copyright (c) 2022, Tinker Twins +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +''' + +################################################################################ + import rospy -from std_msgs.msg import Float32 +from ackermann_msgs.msg import AckermannDriveStamped import sys, select, os if os.name == 'nt': import msvcrt @@ -10,28 +40,25 @@ ################################################################################ -DRIVE_LIMIT = 1 +DRIVE_LIMIT = 5 STEER_LIMIT = 1 -DRIVE_STEP_SIZE = 0.2 -STEER_STEP_SIZE = 0.2 +DRIVE_STEP_SIZE = 1 +STEER_STEP_SIZE = 1 info = """ ------------------------------------- -AutoDRIVE - Nigel Teleoperation Panel +AutoDRIVE-F1TENTH Teleoperation Panel +Developers - Chinmay and Tanmay Samak ------------------------------------- - Q W E A S D X - W/S : Increase/decrease drive command D/A : Increase/decrease steer command Q : Zero steer E : Emergency brake X : Force stop and reset - Press CTRL+C to quit - NOTE: Press keys within this terminal ------------------------------------- """ @@ -75,9 +102,9 @@ def boundDrive(drive_cmd): if os.name != 'nt': settings = termios.tcgetattr(sys.stdin) - rospy.init_node('testbed_teleop') - steer_pub = rospy.Publisher('steer_cmd', Float32, queue_size=10) - drive_pub = rospy.Publisher('drive_cmd', Float32, queue_size=10) + rospy.init_node('key_teleop') + key_teleop_pub = rospy.Publisher('/vesc/low_level/ackermann_cmd_mux/input/teleop', AckermannDriveStamped, queue_size=10) + key_teleop_msg = AckermannDriveStamped() throttle = 0.0 steering = 0.0 @@ -92,9 +119,9 @@ def boundDrive(drive_cmd): elif key == 's' : throttle = boundDrive(throttle - DRIVE_STEP_SIZE) elif key == 'a' : - steering = boundSteer(steering - STEER_STEP_SIZE) - elif key == 'd' : steering = boundSteer(steering + STEER_STEP_SIZE) + elif key == 'd' : + steering = boundSteer(steering - STEER_STEP_SIZE) elif key == 'q' : steering = 0.0 elif key == 'e' : @@ -106,8 +133,11 @@ def boundDrive(drive_cmd): if (key == '\x03'): # CTRL+C break - drive_pub.publish(throttle) - steer_pub.publish(steering) + key_teleop_msg.header.stamp = rospy.Time.now() + key_teleop_msg.header.frame_id = 'base_link' + key_teleop_msg.drive.speed = throttle + key_teleop_msg.drive.steering_angle = steering + key_teleop_pub.publish(key_teleop_msg) except: print(error) @@ -115,8 +145,11 @@ def boundDrive(drive_cmd): finally: throttle = 0.0 steering = 0.0 - drive_pub.publish(throttle) - steer_pub.publish(steering) + key_teleop_msg.header.stamp = rospy.Time.now() + key_teleop_msg.header.frame_id = 'base_link' + key_teleop_msg.drive.speed = throttle + key_teleop_msg.drive.steering_angle = steering + key_teleop_pub.publish(key_teleop_msg) if os.name != 'nt': termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/usb_webcam.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/camera.launch similarity index 100% rename from ROS Workspace/f1tenth/racecar/racecar/launch/usb_webcam.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/camera.launch diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/camera_joy.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/camera_joy.launch new file mode 100644 index 0000000..f40b089 --- /dev/null +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/camera_joy.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/camera_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/camera_key.launch new file mode 100644 index 0000000..a80c937 --- /dev/null +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/camera_key.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/data_recording_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/data_recording_key.launch index f77f25c..9e17ede 100644 --- a/ROS Workspace/f1tenth/racecar/racecar/launch/data_recording_key.launch +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/data_recording_key.launch @@ -5,8 +5,8 @@ - - + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/hector_slam_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/hector_slam_key.launch index 1f6a0f3..20e8808 100644 --- a/ROS Workspace/f1tenth/racecar/racecar/launch/hector_slam_key.launch +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/hector_slam_key.launch @@ -4,8 +4,8 @@ - - + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/lidar.launch similarity index 100% rename from ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/lidar.launch diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan_joy.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/lidar_joy.launch similarity index 100% rename from ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan_joy.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/lidar_joy.launch diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/lidar_key.launch similarity index 84% rename from ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan_key.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/lidar_key.launch index a0e1a11..9157388 100644 --- a/ROS Workspace/f1tenth/racecar/racecar/launch/laser_scan_key.launch +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/lidar_key.launch @@ -1,8 +1,8 @@ - - + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/localization_autodrive_teleop_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/localization_autodrive_key.launch similarity index 98% rename from ROS Workspace/f1tenth/racecar/racecar/launch/localization_autodrive_teleop_key.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/localization_autodrive_key.launch index 87ffc2a..66632f5 100644 --- a/ROS Workspace/f1tenth/racecar/racecar/launch/localization_autodrive_teleop_key.launch +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/localization_autodrive_key.launch @@ -5,7 +5,7 @@ - + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/localization_vesc_teleop_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/localization_vesc_key.launch similarity index 96% rename from ROS Workspace/f1tenth/racecar/racecar/launch/localization_vesc_teleop_key.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/localization_vesc_key.launch index c24e22e..7309f02 100644 --- a/ROS Workspace/f1tenth/racecar/racecar/launch/localization_vesc_teleop_key.launch +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/localization_vesc_key.launch @@ -1,8 +1,8 @@ - - + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/navigation_autodrive.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/navigation_autodrive.launch new file mode 100644 index 0000000..45107f6 --- /dev/null +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/navigation_autodrive.launch @@ -0,0 +1,114 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + # topic where the lidar scans are being published + # topic where to publish the odometry estimations + # whether or not to publish the tf::transform (base_frame->odom_frame) + # frame_id (tf) of the mobile base + # frame_id (tf) to publish the odometry estimations + # leave empty to start at point (0,0) + # execution frequency + # verbose + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/sensors_joy.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/sensors_joy.launch new file mode 100644 index 0000000..0b7dc6e --- /dev/null +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/sensors_joy.launch @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/sensors_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/sensors_key.launch new file mode 100644 index 0000000..b7f6d57 --- /dev/null +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/sensors_key.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_key.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_autodrive_key.launch similarity index 86% rename from ROS Workspace/f1tenth/racecar/racecar/launch/teleop_key.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/teleop_autodrive_key.launch index fb97795..f447ffe 100644 --- a/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_key.launch +++ b/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_autodrive_key.launch @@ -17,7 +17,7 @@ - + @@ -25,7 +25,7 @@ - - + + diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_joy.launch b/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_f1tenth_joy.launch similarity index 100% rename from ROS Workspace/f1tenth/racecar/racecar/launch/teleop_joy.launch rename to ROS Workspace/f1tenth/racecar/racecar/launch/teleop_f1tenth_joy.launch diff --git a/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_joy_readme.txt b/ROS Workspace/f1tenth/racecar/racecar/launch/teleop_f1tenth_joy_readme.txt similarity index 100% rename from ROS Workspace/f1tenth/racecar/racecar/launch/teleop_joy_readme.txt rename to ROS Workspace/f1tenth/racecar/racecar/launch/teleop_f1tenth_joy_readme.txt diff --git a/ROS Workspace/f1tenth/racecar/racecar/rviz/navigation.rviz b/ROS Workspace/f1tenth/racecar/racecar/rviz/navigation.rviz new file mode 100644 index 0000000..2d018fe --- /dev/null +++ b/ROS Workspace/f1tenth/racecar/racecar/rviz/navigation.rviz @@ -0,0 +1,299 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.699999988079071 + Tree Height: 849 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + - /Current View1/Focal Point1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 100 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 5.510126113891602 + Min Value: -2.0559444427490234 + Value: true + Axis: Y + Channel Name: intensity + Class: rviz/LaserScan + Color: 239; 41; 41 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Points + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Class: rviz/Axes + Enabled: false + Length: 0.25999999046325684 + Name: Vehicle Frame + Radius: 0.05000000074505806 + Reference Frame: base_link + Value: false + - Alpha: 1 + Class: rviz/Polygon + Color: 25; 255; 0 + Enabled: true + Name: Vehicle Footprint + Topic: /planner/local_costmap/footprint + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 255; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: AMCL Belief + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /particlecloud + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 0.25999999046325684 + Axes Radius: 0.05000000074505806 + Class: rviz/PoseWithCovariance + Color: 255; 25; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: AMCL Pose + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Axes + Topic: /amcl_pose + Unreliable: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Global Costmap + Topic: /planner/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Local Costmap + Topic: /planner/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Axes Length: 0.25999999046325684 + Axes Radius: 0.05000000074505806 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Goal + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Axes + Topic: /planner/current_goal + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.05000000074505806 + Name: Global Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /planner/NavfnROS/plan + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 237; 212; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.05000000074505806 + Name: Local Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /planner/TebLocalPlannerROS/local_plan + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.978835105895996 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.4846252501010895 + Y: 1.0217820405960083 + Z: 0.0004830139805562794 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.140000104904175 + Saved: ~ +Window Geometry: + Displays: + collapsed: true + Height: 1056 + Hide Left Dock: true + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000156000003dcfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000027000003dc000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000403fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000000000000403000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006500000000000000073f000004f300fffffffb0000000800540069006d006501000000000000045000000000000000000000073f000003dc00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1855 + X: 65 + Y: 24 diff --git a/ROS Workspace/f1tenth/racecar/racecar/scripts/key_teleop.py b/ROS Workspace/f1tenth/racecar/racecar/scripts/key_teleop.py deleted file mode 100644 index e610c22..0000000 --- a/ROS Workspace/f1tenth/racecar/racecar/scripts/key_teleop.py +++ /dev/null @@ -1,155 +0,0 @@ -#!/usr/bin/env python - -''' -BSD 2-Clause License - -Copyright (c) 2022, Tinker Twins -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -''' - -################################################################################ - -import rospy -from ackermann_msgs.msg import AckermannDriveStamped -import sys, select, os -if os.name == 'nt': - import msvcrt -else: - import tty, termios - -################################################################################ - -DRIVE_LIMIT = 5 -STEER_LIMIT = 1 -DRIVE_STEP_SIZE = 1 -STEER_STEP_SIZE = 1 - -info = """ -------------------------------------- -F1TENTH - RaceCar Teleoperation Panel -Developers - Chinmay and Tanmay Samak -------------------------------------- - Q W E - A S D - X -W/S : Increase/decrease drive command -D/A : Increase/decrease steer command -Q : Zero steer -E : Emergency brake -X : Force stop and reset -Press CTRL+C to quit -NOTE: Press keys within this terminal -------------------------------------- -""" - -error = """ -ERROR: Communication failed! -""" - -def getKey(): - if os.name == 'nt': - return msvcrt.getch() - tty.setraw(sys.stdin.fileno()) - rlist, _, _ = select.select([sys.stdin], [], [], 0.1) - if rlist: - key = sys.stdin.read(1) - else: - key = '' - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) - return key - -def constrain(input, low, high): - if input < low: - input = low - elif input > high: - input = high - else: - input = input - return input - -def boundSteer(steer_cmd): - steer_cmd = constrain(steer_cmd, -STEER_LIMIT, STEER_LIMIT) - return steer_cmd - -def boundDrive(drive_cmd): - drive_cmd = constrain(drive_cmd, -DRIVE_LIMIT, DRIVE_LIMIT) - return drive_cmd - -################################################################################ - -if __name__=="__main__": - if os.name != 'nt': - settings = termios.tcgetattr(sys.stdin) - - rospy.init_node('key_teleop') - key_teleop_pub = rospy.Publisher('/vesc/low_level/ackermann_cmd_mux/input/teleop', AckermannDriveStamped, queue_size=10) - key_teleop_msg = AckermannDriveStamped() - - throttle = 0.0 - steering = 0.0 - - try: - print(info) - - while(1): - key = getKey() - if key == 'w' : - throttle = boundDrive(throttle + DRIVE_STEP_SIZE) - elif key == 's' : - throttle = boundDrive(throttle - DRIVE_STEP_SIZE) - elif key == 'a' : - steering = boundSteer(steering + STEER_STEP_SIZE) - elif key == 'd' : - steering = boundSteer(steering - STEER_STEP_SIZE) - elif key == 'q' : - steering = 0.0 - elif key == 'e' : - throttle = 0.0 - elif key == 'x' : - throttle = 0.0 - steering = 0.0 - else: - if (key == '\x03'): # CTRL+C - break - - key_teleop_msg.header.stamp = rospy.Time.now() - key_teleop_msg.header.frame_id = 'base_link' - key_teleop_msg.drive.speed = throttle - key_teleop_msg.drive.steering_angle = steering - key_teleop_pub.publish(key_teleop_msg) - - except: - print(error) - - finally: - throttle = 0.0 - steering = 0.0 - key_teleop_msg.header.stamp = rospy.Time.now() - key_teleop_msg.header.frame_id = 'base_link' - key_teleop_msg.drive.speed = throttle - key_teleop_msg.drive.steering_angle = steering - key_teleop_pub.publish(key_teleop_msg) - - if os.name != 'nt': - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)