Skip to content

Commit

Permalink
create launch_segbot_base package (#105)
Browse files Browse the repository at this point in the history
  • Loading branch information
jack-oquin committed Feb 27, 2018
1 parent 8b92c9f commit 45bdb69
Show file tree
Hide file tree
Showing 12 changed files with 202 additions and 14 deletions.
14 changes: 14 additions & 0 deletions launch_segbot_base/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(launch_segbot_base)

find_package(catkin REQUIRED)
catkin_package()

install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch)

# unit tests are enabled selectively
if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(launch)
endif()
69 changes: 69 additions & 0 deletions launch_segbot_base/launch/common.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
<!-- common launch for all segbot bases -->
<launch>

<arg name="global_frame" default="level_mux_map" />
<arg name="gui" default="true" />
<arg name="laser_max_range" default="4.0" /> <!-- ??? -->
<arg name="localization_scan_topic" default="scan_filtered" />
<arg name="move_base_config" default="segbotv2" />
<arg name="multimap_file"
default="$(find utexas_gdc)/maps/real/multimap/multimap.yaml" />
<arg name="rviz" default="true" />

<!-- ********* multi-level maps ******** -->

<node name="multi_level_map_server" pkg="multi_level_map_server"
type="multi_level_map_server">
<param name="map_file" value="$(arg multimap_file)" />
</node>

<!-- Set the default level this robot starts on -->
<param name="level_mux/default_current_level" value="3rdFloor" />

<!-- also launch the level multiplexer and the level selector GUI -->
<node name="level_mux" pkg="multi_level_map_utils" type="level_mux">
<param name="global_frame_id" value="$(arg global_frame)" />
</node>
<node name="level_selector" pkg="multi_level_map_utils" type="level_selector" />

<!-- launch passive (no tours enabled) virtour -->
<include file="$(find bwi_virtour)/launch/virtour_passive.launch"/>

<!-- Start logging selected topics -->
<include file="$(find bwi_logging)/launch/record.launch" />

<!-- localization -->
<include file="$(find segbot_navigation)/launch/amcl.launch">
<arg name="map_service" value="level_mux/static_map" />
<arg name="map_topic" value="level_mux/map" />
<arg name="map_frame_id" value="level_mux_map" />
<arg name="base_frame_id" value="base_footprint" />
<arg name="odom_frame_id" value="odom" />
<arg name="laser_max_range" value="$(arg laser_max_range)" />
<arg name="scan_topic" value="$(arg localization_scan_topic)" />
</include>

<!-- interruptable physical and logical navigation -->
<include file="$(find segbot_navigation)/launch/interruptable_navigation.launch">
<arg name="global_frame" value="$(arg global_frame)" />
<arg name="config" default="$(arg move_base_config)" />
</include>

<!-- knowledge representation, reasoning, and planing -->
<include file="$(find bwi_kr_execution)/launch/bwi_kr_execution.launch">
<arg name="domain" value="$(find bwi_kr_execution)/domain/" />
<arg name="simulation" value="false" />
</include>

<!-- ******* graphical user interface ********* -->

<!-- vizualization -->
<node name="rviz" type="rviz_runner" pkg="segbot_navigation"
if="$(arg rviz)" />

<!-- question dialog gui -->
<node name="gui" type="question_dialog_plugin" pkg="bwi_rqt_plugins"
if="$(arg gui)" />

</launch>

17 changes: 17 additions & 0 deletions launch_segbot_base/launch/v2.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<!-- segbot_v2 base -->
<launch>

<!-- common components -->
<include file="$(find launch_segbot_base)/launch/common.launch">
<arg name="move_base_config" default="segbotv2" />
</include>

<!-- robot base driver -->
<include file="$(find segbot_bringup)/launch/segbot_v2.launch">
<arg name="gui" value="$(arg gui)" />
</include>

<!-- other devices -->
<include file="$(find segbot_bringup)/launch/includes/auxiliary.segbot_v2.launch.xml"/>

</launch>
17 changes: 17 additions & 0 deletions launch_segbot_base/launch/v3.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<!-- segbot_v3 base -->
<launch>

<!-- common components -->
<include file="$(find launch_segbot_base)/launch/common.launch">
<arg name="move_base_config" value="segbotv3" />
</include>

<!-- robot base driver -->
<include file="$(find segbot_bringup)/launch/segbot_v3.launch">
<arg name="gui" value="$(arg gui)" />
</include>

<!-- other devices -->
<include file="$(find segbot_bringup)/launch/includes/auxiliary.segbot_v3.launch.xml"/>

</launch>
34 changes: 34 additions & 0 deletions launch_segbot_base/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<package format="2">
<name>launch_segbot_base</name>
<version>0.3.3</version>
<description>
Top-level ROS launch scripts for the Building-Wide Intelligence
(BWI) project of the University of Texas at Austin.

This package launches the base for any of the various BWI segbot
models.
</description>

<license>BSD</license>

<url type="repository">https://github.com/utexas-bwi/segbot</url>
<url type="bugtracker">https://github.com/utexas-bwi/segbot/issues</url>

<maintainer email="jack.oquin@gmail.com">Jack O'Quin</maintainer>
<author>Jack O'Quin</author>
<author>Piyush Khandelwal</author>

<buildtool_depend>catkin</buildtool_depend>

<exec_depend>bwi_kr_execution</exec_depend>
<exec_depend>bwi_rqt_plugins</exec_depend>
<exec_depend>bwi_virtour</exec_depend>
<exec_depend>multi_level_map_server</exec_depend>
<exec_depend>multi_level_map_utils</exec_depend>
<exec_depend>segbot_bringup</exec_depend> <!-- eliminate this depend -->
<exec_depend>segbot_navigation</exec_depend>
<exec_depend>utexas_gdc</exec_depend>

<test_depend>roslaunch</test_depend>

</package>
1 change: 1 addition & 0 deletions segbot_gazebo/launch/segbot_navigation.launch
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
<!-- this does not seem to be used anymore -->
<launch>

<arg name="robot_configuration" default="$(find segbot_bringup)/launch/includes/auxiliary.segbot_v1.hokuyo_only.launch.xml" />
Expand Down
2 changes: 0 additions & 2 deletions segbot_navigation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,4 @@ if (CATKIN_ENABLE_TESTING)
roslaunch_add_file_check(launch/gmapping.launch)
roslaunch_add_file_check(launch/move_base_eband.launch)
roslaunch_add_file_check(launch/rviz.launch)
## launch/navigation.launch not tested until
## ros-drivers/openni_launch#10 is fixed.
endif ()
28 changes: 28 additions & 0 deletions segbot_navigation/launch/interruptable_navigation.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<!-- interruptable physical and logical navigation -->
<launch>

<arg name="global_frame" default="level_mux_map" />
<arg name="move_base_config" default="segbotv2" />

<!-- interruptable action server -->
<node name="move_base_interruptable" pkg="segbot_navigation"
type="move_base_interruptable_server" />
<node name="move_base_interruptable_simple" pkg="segbot_navigation"
type="move_base_interruptable_simple" />

<!-- move_base with elastic band local planner -->
<include file="$(find segbot_navigation)/launch/move_base_eband.launch">
<arg name="map_topic" value="bwi_logical_navigator/map" />
<arg name="move_base_server" value="move_base_interruptable" />
<arg name="global_frame" value="$(arg global_frame)" />
<arg name="config" default="$(arg move_base_config)" />
</include>

<!-- logical navigation. -->
<node name="bwi_logical_navigator" pkg="bwi_logical_translator"
type="bwi_logical_navigator">
<param name="global_frame_id" value="$(arg global_frame)" />
<remap from="move_base" to="move_base_interruptable" />
</node>

</launch>
31 changes: 19 additions & 12 deletions segbot_navigation/launch/move_base_eband.launch
Original file line number Diff line number Diff line change
Expand Up @@ -12,23 +12,30 @@
<arg name="eband_rotational_threshold_multiplier" default="1.0" />
<arg name="eband_disallow_hysteresis" default="false" />

<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" launch-prefix="$(arg prefix)">
<rosparam file="$(find segbot_navigation)/config/$(arg config)/move_base_params.yaml" command="load" />
<rosparam file="$(find segbot_navigation)/config/$(arg config)/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find segbot_navigation)/config/$(arg config)/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find segbot_navigation)/config/$(arg config)/local_costmap_params.yaml" command="load" />
<rosparam file="$(find segbot_navigation)/config/$(arg config)/global_costmap_params.yaml" command="load" />
<rosparam file="$(find segbot_navigation)/config/$(arg config)/eband_planner_params.yaml" command="load"/>
<node pkg="move_base" type="move_base" name="move_base"
respawn="false" output="screen" launch-prefix="$(arg prefix)">
<rosparam command="load"
file="$(find segbot_navigation)/config/$(arg config)/move_base_params.yaml"/>
<rosparam command="load" ns="global_costmap"
file="$(find segbot_navigation)/config/$(arg config)/costmap_common_params.yaml"/>
<rosparam command="load" ns="local_costmap"
file="$(find segbot_navigation)/config/$(arg config)/costmap_common_params.yaml"/>
<rosparam command="load"
file="$(find segbot_navigation)/config/$(arg config)/local_costmap_params.yaml"/>
<rosparam command="load"
file="$(find segbot_navigation)/config/$(arg config)/global_costmap_params.yaml"/>
<rosparam command="load"
file="$(find segbot_navigation)/config/$(arg config)/eband_planner_params.yaml"/>

<param name="base_local_planner" value="eband_local_planner/EBandPlannerROS" />

<param name="global_costmap/map_topic" value="$(arg map_topic)"/>

<param name="local_costmap/global_frame" value="$(arg global_frame)"/>
<param name="global_costmap/global_frame" value="$(arg global_frame)"/>

<param name="EBandPlannerROS/rotational_threshold_multiplier" value="$(arg eband_rotational_threshold_multiplier)" />
<param name="EBandPlannerROS/disallow_hysteresis" value="$(arg eband_disallow_hysteresis)" />
<param name="base_local_planner" value="eband_local_planner/EBandPlannerROS" />
<param name="EBandPlannerROS/rotational_threshold_multiplier"
value="$(arg eband_rotational_threshold_multiplier)" />
<param name="EBandPlannerROS/disallow_hysteresis"
value="$(arg eband_disallow_hysteresis)" />

<remap from="move_base" to="$(arg move_base_server)" />
</node>
Expand Down
1 change: 1 addition & 0 deletions segbot_navigation/launch/navigation.launch
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
<!-- this does not seem to be used anymore -->
<launch>

<arg name="map_file" default="$(find utexas_gdc)/maps/real/3ne/3ne.yaml" />
Expand Down
1 change: 1 addition & 0 deletions segbot_navigation/launch/navigation_v2.launch
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
<!-- this does not seem to be used anymore -->
<launch>

<arg name="map_file" default="$(find utexas_gdc)/maps/real/3ne/3ne.yaml" />
Expand Down
1 change: 1 addition & 0 deletions segbot_navigation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<depend>std_srvs</depend>

<exec_depend>amcl</exec_depend>
<exec_depend>bwi_logical_translator</exec_depend>
<exec_depend>eband_local_planner</exec_depend>
<exec_depend>gmapping</exec_depend>
<exec_depend>map_server</exec_depend>
Expand Down

0 comments on commit 45bdb69

Please sign in to comment.