Skip to content
This repository has been archived by the owner on Apr 12, 2024. It is now read-only.

Commit

Permalink
Merge pull request #11 from Autonomous-Motorsports-Purdue/migrate_kar…
Browse files Browse the repository at this point in the history
…t_to_sim

Migrate Kart Launch Architecture to Simulation Launches
  • Loading branch information
zghera authored Sep 25, 2021
2 parents f3bea0f + f19e5a5 commit 29cbca2
Show file tree
Hide file tree
Showing 10 changed files with 153 additions and 78 deletions.
1 change: 1 addition & 0 deletions src/kart_2dnav/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(catkin REQUIRED COMPONENTS
velodyne_pointcloud
pointcloud_to_laserscan
laser_scan_matcher_odom
stage_ros_mod_tf
hector_mapping
base_local_planner
global_planner
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
<?xml version="1.0"?>

<!--
Simulate a carlike robot with the teb_local_planner in stage:
- stage
- map_server
- move_base
- static map
- amcl
- rviz view
-->
<launch>

<!-- ************** Global Parameters *************** -->
<param name="/use_sim_time" value="true"/>

<!-- ************** Stage Simulator *************** -->
<node pkg="stage_ros" type="stageros" name="stageros" args="$(find kart_2dnav)/stage/autocross_track.world">
<!-- Use top/scan to match naming used for output scan topic from pointcloud_to_laserscan -->
<remap from="base_scan" to="top/scan"/>
</node>

<!-- ************** ROS Navigation Stack (move_base) *************** -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/costmap_common_params.yaml" command="load" ns="global_costmap" />
<!-- Modified teb_local_planner_tutorials version to set laserscan input to move_base come from top/scan -->
<rosparam file="$(find kart_2dnav)/params/sim_params/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/local_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/global_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/teb_local_planner_params.yaml" command="load" />

<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="planner_frequency" value="1.0" />
<param name="planner_patience" value="5.0" />

<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<param name="controller_frequency" value="5.0" />
<param name="controller_patience" value="15.0" />

<!-- Our carlike robot is not able to rotate in place -->
<param name="clearing_rotation_allowed" value="false" />
</node>

<!-- Run the goal setting script to navigate in SLAM mode -->
<node pkg="slam_mode_goal" type="slam_mode_goal" name="slam_mode_goal" output="screen">
</node>

<!-- MICROCONTROLLER COMM -->
<!-- Run the communication script to enable and start communicating with microcontroller -->
<node pkg="ti_comm" type="ti_comm_node" name="ti_comm_node" output="screen" />

<!-- ****** Use a Known (Static) Map ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find kart_2dnav)/maps/autocross.yaml" output="screen">
<param name="frame_id" value="map"/>
</node>

<node pkg="amcl" type="amcl" name="amcl" output="screen">
<!-- Change default subscribed scan topic from scan to top/scan -->
<remap from="scan" to="top/scan"/>

<param name="initial_pose_x" value="4"/>
<param name="initial_pose_y" value="1.5"/>
<param name="initial_pose_a" value="0"/>
</node>

<!-- **************** Visualisation **************** -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find teb_local_planner_tutorials)/cfg/rviz_navigation.rviz"/>

</launch>
4 changes: 3 additions & 1 deletion src/kart_2dnav/launch/kart_rosbag.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

<launch>
<!-- This parameter instructs the system to use a simulated clock.
This file is meant soely for testing with bagged environment data
(rosbags) so that is why we set it here.
Expand Down Expand Up @@ -88,5 +89,6 @@
Note: This should only be set when running the system with simulated
sensor data (rosbags).
-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find kart_2dnav)/params/kart_rviz.rviz" />
<node name="rviz" pkg="rviz" type="rviz"
args="-d $(find kart_2dnav)/params/kart_rviz.rviz" />
</launch>
97 changes: 47 additions & 50 deletions src/kart_2dnav/launch/sim_autocross_track.launch
Original file line number Diff line number Diff line change
@@ -1,69 +1,66 @@
<?xml version="1.0"?>

<!--
Simulate a carlike robot with the teb_local_planner in stage:
- stage
- map_server
- move_base
- static map
- amcl
- rviz view
-->
<launch>

<!-- ************** Global Parameters *************** -->
<!-- SIMULATION CONFIGURATION -->
<param name="/use_sim_time" value="true"/>

<!-- ************** Stage Simulator *************** -->
<node pkg="stage_ros" type="stageros" name="stageros" args="$(find kart_2dnav)/stage/autocross_track.world">
<!-- Use top/scan to match naming used for output scan topic from pointcloud_to_laserscan -->
<!-- Launch the RViz simulation -->
<node pkg="stage_ros_mod_tf" type="stage_ros_mod_tf_node"
name="stage_ros_mod_tf_node"
args="$(find kart_2dnav)/stage/autocross_track.world">
<!-- Remap the scan topic to top/scan to match naming used for output
scan topic from pointcloud_to_laserscan -->
<remap from="base_scan" to="top/scan"/>
</node>

<!-- ************** ROS Navigation Stack (move_base) *************** -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/costmap_common_params.yaml" command="load" ns="global_costmap" />
<!-- Modified teb_local_planner_tutorials version to set laserscan input to move_base come from top/scan -->
<rosparam file="$(find kart_2dnav)/params/sim_params/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/local_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/global_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/carlike/teb_local_planner_params.yaml" command="load" />

<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="planner_frequency" value="1.0" />
<param name="planner_patience" value="5.0" />

<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<param name="controller_frequency" value="5.0" />
<param name="controller_patience" value="15.0" />
<!-- LASER ODOMETRY -->
<!-- This node is responsible for taking incremental 2D laserscans (/top/scan)
and outputting estimated odometry information as a tf (odom->base_link)
and by publishing nav_msgs/Odometry messages to the /odom topic. -->
<node pkg="laser_scan_matcher_odom" type="laser_scan_matcher_node_odom"
name="laser_scan_matcher_node_odom" output="screen">
<remap from="scan" to="/top/scan" />
<rosparam file="$(find kart_2dnav)/params/laser_scan_matcher_params.yaml"
command="load" />
</node>

<!-- Our carlike robot is not able to rotate in place -->
<param name="clearing_rotation_allowed" value="false" />
</node>
<!-- SLAM: LOCALIZATION & MAPPING -->
<!-- Run the SLAM package, HectorMapping, that takes in 2D laser scans
(/top/scan) and publishes topics for the created map (/map) and
estimated pose (/slam_out_pose) of the kart relative to the map.
This node is also responsible for publishing the tf map->odom. -->
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<remap from="scan" to="/top/scan" />
<rosparam file="$(find kart_2dnav)/params/hector_mapping_params.yaml" command="load" />
</node>

<!-- Run the goal setting script to navigate in SLAM mode -->
<!-- GOAL SETTING -->
<!-- Run the goal setting algorithm to navigate without a preliminary map (lap 1).
This node takes 2D laser scans (/top/scan) then constructs a goal message and
creates an ActionClient to sends the goal as ROS actions to SimpleActionServer
on move_base. -->
<!-- TODO: Figure out how to incorporate ROS params with goal setting script -->
<node pkg="slam_mode_goal" type="slam_mode_goal" name="slam_mode_goal" output="screen">
</node>

<!-- ROS NAVIGATION STACK -->
<!-- Configure and run move_base to set up the ROS Navigation Stack. -->
<!-- More details on inputs/outputs can be found in move_base.launch -->
<include file="$(find kart_2dnav)/launch/move_base.launch" />

<!-- MICROCONTROLLER COMM -->
<!-- Run the communication script to enable and start communicating with microcontroller -->
<!-- Run the communication script to enable and start communicating with the
microcontroller. This node subscribed to the /cmd_vel topic published by
move_base and then then sends packets containing the velocity and steering
angle to the MCU over a serial connection. -->
<node pkg="ti_comm" type="ti_comm_node" name="ti_comm_node" output="screen" />

<!-- ****** Use a Known (Static) Map ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find kart_2dnav)/maps/autocross.yaml" output="screen">
<param name="frame_id" value="map"/>
</node>

<node pkg="amcl" type="amcl" name="amcl" output="screen">
<!-- Change default subscribed scan topic from scan to top/scan -->
<remap from="scan" to="top/scan"/>

<param name="initial_pose_x" value="4"/>
<param name="initial_pose_y" value="1.5"/>
<param name="initial_pose_a" value="0"/>
</node>
<!-- Launch rviz with the configuration file in order to visualize incoming data
<!-- **************** Visualisation **************** -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find teb_local_planner_tutorials)/cfg/rviz_navigation.rviz"/>
Note: This should only be set when running the system with simulated
sensor data (rosbags).
-->
<node name="rviz" pkg="rviz" type="rviz"
args="-d $(find kart_2dnav)/params/kart_rviz.rviz" />

</launch>
4 changes: 1 addition & 3 deletions src/kart_2dnav/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -57,15 +57,13 @@
<depend>velodyne_pointcloud</depend>
<depend>pointcloud_to_laserscan</depend>
<depend>laser_scan_matcher_odom</depend>
<depend>stage_ros_mod_tf</depend>
<depend>hector_mapping</depend>
<depend>base_local_planner</depend>
<depend>global_planner</depend>
<depend>move_base</depend>
<depend>teb_local_planner</depend>
<depend>teb_local_planner_tutorials</depend>
<!-- <depend>sbg_driver</depend>
<depend>sbg_to_imu</depend>
<depend>imu_filter_madgwick</depend> -->

<!-- The export tag contains other, unspecified, tags -->
<export>
Expand Down
24 changes: 14 additions & 10 deletions src/kart_2dnav/params/costmap_common_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,26 @@
# See http://wiki.ros.org/costmap_2d for details.

# TODO(Issue #8): Correct this values for our kart's specific physical attr/sensors.
footprint: [ [0.7112, 0.4064], [0.7112, -1.524], [-0.7112, -1.524], [-0.7112, 0.4064] ]
# robot footprint in meters
# 1. (maybe) footprint of our go-kart
# footprint: [ [0.7112, 0.4064], [0.7112, -1.524], [-0.7112, -1.524], [-0.7112, 0.4064] ]
# 2. footprint used by teb_local_planner tutorials. Use this for simulation as of now
footprint: [ [-0.1,-0.125], [0.5,-0.125], [0.5,0.125], [-0.1,0.125] ]

transform_tolerance: 0.2
map_type: costmap

obstacle_layer:
enabled: true
# TODO(Issue #8): Correct this values for our kart's specific physical attr/sensors.
obstacle_range: 2.5
# TODO(Issue #8): Correct this values for our kart's specific physical attr/sensors.
max_obstacle_height: 2.0
obstacle_range: 3.0
# TODO(Issue #8): Will likely change in tandem with obstacle_range above.
raytrace_range: 3.0
inflation_radius: 0.5
raytrace_range: 3.5
# TODO(Issue #8): Correct this values for our kart's specific physical attr/sensors.
max_obstacle_height: 2.0
min_obstacle_height: 0.0
# ------------------------
inflation_radius: 0.2
track_unknown_space: false
combination_method: 1
observation_sources: laser_scan_sensor point_cloud_sensor
Expand All @@ -26,10 +32,8 @@ obstacle_layer:

inflation_layer:
enabled: true
cost_scaling_factor: 10.0 # exponential rate at which the obstacle
# cost drops off [default]
inflation_radius: 0.5 # max distance from an obstacle at which costs
# are incurred for planning paths [default]
cost_scaling_factor: 10.0
inflation_radius: 0.5

static_layer:
enabled: true
Expand Down
7 changes: 4 additions & 3 deletions src/kart_2dnav/params/global_costmap_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,12 @@ global_costmap:
global_frame: "map"
robot_base_frame: "base_link"
update_frequency: 5.0
public_frequency: 2.5
static_map: false
public_frequency: 0.5 # match teb_local_planner_tutorials
static_map: false # we are not using a map server / existing map

transform_tolerance: 0.5
transform_tolerance: 0.2
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}

7 changes: 3 additions & 4 deletions src/kart_2dnav/params/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
# All parameters are set to default values unless otherwise noted.
# See http://wiki.ros.org/costmap_2d for details.


local_costmap:
global_frame: "map"
robot_base_frame: "base_link"
Expand All @@ -11,9 +10,9 @@ local_costmap:
rolling_window: true
# TODO: Revisit width, height, resolution, etc. here once we start looking
# at creating a map from first lap.
width: 6.0
height: 6.0
resolution: 0.05
width: 5.5
height: 5.5
resolution: 0.1
transform_tolerance: 0.5

plugins:
Expand Down
18 changes: 11 additions & 7 deletions src/kart_2dnav/params/teb_local_planner_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,14 @@ TebLocalPlannerROS:

odom_topic: "odom"

# Trajectory of the kart
# Trajectory

teb_autosize: True
dt_ref: 1
dt_hysteresis: 0.1
global_plan_overwrite_orientation: True
allow_init_with_backwards_motion: True
max_global_plan_lookahead_dist: 5.0
max_global_plan_lookahead_dist: 3.0
global_plan_viapoint_sep: -0.1
global_plan_prune_distance: 1
exact_arc_length: False
Expand All @@ -32,14 +32,18 @@ TebLocalPlannerROS:
acc_lim_x: 0.5
acc_lim_theta: 0.5

min_turning_radius: 0.51
wheelbase: 1.0541
min_turning_radius: 0.5 # (maybe) phyiscal val: 0.51
wheelbase: 0.4 # (maybe) phyiscal val: 1.0541
cmd_angle_instead_rotvel: True

footprint_model:
type: "polygon"
vertices: [ [0.7112, 0.4064], [0.7112, -1.524],
[-0.7112, -1.524], [-0.7112, 0.4064] ]
# 1. (maybe) footprint of our go-kart
#vertices: [ [0.7112, 0.4064], [0.7112, -1.524],
# [-0.7112, -1.524], [-0.7112, 0.4064] ]
# 2. footprint used by teb_local_planner tutorials.
# Use this for simulation as of now
vertices: [[-0.1,-0.125], [0.5,-0.125], [0.5,0.125], [-0.1,0.125]]
# ---------------------------------

# Goal Tolerance
Expand All @@ -51,7 +55,7 @@ TebLocalPlannerROS:

# Obstacles

min_obstacle_dist: 0.5
min_obstacle_dist: 0.25
inflation_dist: 0.6
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 1.0
Expand Down

0 comments on commit 29cbca2

Please sign in to comment.