Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/launch file organization #95

Open
wants to merge 6 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
23 changes: 23 additions & 0 deletions lunabot_bringup/launch/autonomy.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<launch>
<arg name="slam" default="true"/>
<include if="$(arg slam)" file="$(find lunabot_bringup)/launch/slam.launch"/>

<node pkg="lunabot_control" type="effort_factory.py" name="effort_factory" output="screen"/>

<node pkg="lunabot_control" type="differential_drive_controller.py" name="differential_drive_controller" output="screen"/>

<group ns="nav">
<node pkg="lunabot_control" type="mpc_node" name="mpc_node" output="screen"/>

<node name="global_planner_node" pkg="lunabot_nav" type="dstar_node.py" output="screen" respawn="true">
<!-- <rosparam file="$(find lunabot_config)/config/rrtstar.yml" command="load"/> -->
</node>
</group>

<group ns="maps">
<node name="costmap_node" pkg="lunabot_perception" type="costmap_node" output="screen">
<rosparam file="$(find lunabot_config)/config/global_costmap.yml" command="load" ns="global_costmap" />
</node>
</group>
</launch>
39 changes: 4 additions & 35 deletions lunabot_bringup/launch/robot.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,49 +2,18 @@
<launch>
<arg name="autonomy" default="false" />
<arg name="record" default="true" />
<arg name="teensy" default="true" />
<arg name="cameras" default="true" />
<arg name="overhead" default="true" />
<arg name="slam" default="true" />
<arg name="exp_name" default="exp" />

<node if="$(arg teensy)" name="teensy_driver" pkg="lunabot_embedded" type="teensy_driver_node" output="screen"/>

<include file="$(find lunabot_bringup)/launch/teensy.launch"/>
<include if="$(arg cameras)" file="$(find lunabot_perception)/launch/cameras.launch"/>
<include if="$(arg overhead)" file="$(find lunabot_bringup)/launch/overhead.launch"/>
<include if="$(arg record)" file="$(find lunabot_bringup)/launch/record.launch">
<arg name="exp_name" value="$(arg exp_name)"/>
</include>

<group if="$(arg autonomy)">

<include if="$(arg slam)" file="$(find rtabmap_ros)/launch/rtabmap.launch" >
<arg name="rtabmap_args" value="--delete_db_on_start"/>
<arg name="depth_topic" value="/d455_back/camera/aligned_depth_to_color/image_raw"/>
<arg name="rgb_topic" value="/d455_back/camera/color/image_rect_color"/>
<arg name="camera_info_topic" value="/d455_back/camera/color/camera_info"/>
<arg name="rtabmapviz" value="false" />
<arg name="imu_topic" value="/imu" />
<arg name="frame_id" value="base_link" />
</include>

<node pkg="lunabot_control" type="effort_factory.py" name="effort_factory" output="screen"/>

<node pkg="lunabot_control" type="differential_drive_controller.py" name="differential_drive_controller" output="screen"/>

<group ns="nav">
<node pkg="lunabot_control" type="mpc_node" name="mpc_node" output="screen"/>

<node name="global_planner_node" pkg="lunabot_nav" type="dstar_node.py" output="screen" respawn="true">
<!-- <rosparam file="$(find lunabot_config)/config/rrtstar.yml" command="load"/> -->
</node>
</group>

<group ns="maps">
<node name="costmap_node" pkg="lunabot_perception" type="costmap_node" output="screen">
<rosparam file="$(find lunabot_config)/config/global_costmap.yml" command="load" ns="global_costmap" />
</node>
</group>

</group>
<include if="$(arg autonomy)" file="$(find lunabot_bringup)/launch/autonomy.launch">
<arg name="slam" value="$(arg slam)"/>
</include>
</launch>
12 changes: 12 additions & 0 deletions lunabot_bringup/launch/slam.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<?xml version="1.0"?>
<launch>
<include file="$(find rtabmap_ros)/launch/rtabmap.launch">
<arg name="rtabmap_args" value="--delete_db_on_start"/>
<arg name="depth_topic" value="/d455_back/camera/aligned_depth_to_color/image_raw"/>
<arg name="rgb_topic" value="/d455_back/camera/color/image_rect_color"/>
<arg name="camera_info_topic" value="/d455_back/camera/color/camera_info"/>
<arg name="rtabmapviz" value="false" />
<arg name="imu_topic" value="/imu" />
<arg name="frame_id" value="base_link" />
</include>
</launch>
4 changes: 4 additions & 0 deletions lunabot_bringup/launch/teensy.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<?xml version="1.0"?>
<launch>
<node name="teensy_driver" pkg="lunabot_embedded" type="teensy_driver_node" output="screen"/>
</launch>
Loading