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

Migrate Kart Launch Architecture to Simulation Launches #11

Merged
merged 15 commits into from
Sep 25, 2021
Merged
Show file tree
Hide file tree
Changes from 11 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
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>
122 changes: 73 additions & 49 deletions src/kart_2dnav/launch/sim_autocross_track.launch
Original file line number Diff line number Diff line change
@@ -1,69 +1,93 @@
<?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_mod_tf" type="stage_ros_mod_tf_node" name="stage_ros_mod_tf_node" 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" />
<!-- 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>

<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="planner_frequency" value="1.0" />
<param name="planner_patience" value="5.0" />
<!-- 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>

<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<param name="controller_frequency" value="5.0" />
<param name="controller_patience" value="15.0" />
<!-- 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>

<!-- Our carlike robot is not able to rotate in place -->
<param name="clearing_rotation_allowed" value="false" />
</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" />
-->
<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" />

<!-- 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">
<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>


<!-- 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