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

Adding support for nav2D flat nav. Adding some existing ROS params to… #105

Open
wants to merge 4 commits into
base: indigo-devel
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
24 changes: 24 additions & 0 deletions magni_demos/launch/simple_nav_map_flat.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<!--
This launch file brings up a simple navigation system using fiducials [1]
and move_basic [2].
A special mode that removes roll and pitch from fiducials used for mapping is enabled

[1] http://wiki.ros.org/fiducials
[2] http://wiki.ros.org/move_basic
-->
<launch>
<!--
This parameter is used to specify what level of capabilites
the robot should have after this launch file.

Possible values are 'core', 'teleop', and 'navigation'

Since this launch brings up enough to do navigation,
we set it to 'navigation'.
-->
<param name="ubiquity_robot_mode" type="string" value="navigation"/>

<include file="$(find magni_nav)/launch/move_basic.launch" />
<include file="$(find magni_nav)/launch/aruco_nav_map_flat.launch" />
</launch>

13 changes: 12 additions & 1 deletion magni_demos/launch/simple_navigation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,11 @@
[2] http://wiki.ros.org/move_basic
-->
<launch>
<arg name="fiducial_len" default="0.140"/>
<arg name="read_only_map" default="false"/>
<arg name="navigate_flat" default="false"/>
<arg name="fiducials_flat" default="false"/>
<arg name="verbose_info" default="false"/>
<!--
This parameter is used to specify what level of capabilites
the robot should have after this launch file.
Expand All @@ -18,6 +23,12 @@
<param name="ubiquity_robot_mode" type="string" value="navigation"/>

<include file="$(find magni_nav)/launch/move_basic.launch" />
<include file="$(find magni_nav)/launch/aruco.launch" />
<include file="$(find magni_nav)/launch/aruco.launch">
<arg name="fiducial_len" value="$(arg fiducial_len)" />
<arg name="read_only_map" value="$(arg read_only_map)"/>
<arg name="navigate_flat" value="$(arg navigate_flat)"/>
<arg name="fiducials_flat" value="$(arg fiducials_flat)"/>
<arg name="verbose_info" value="$(arg verbose_info)"/>
</include>
</launch>

23 changes: 23 additions & 0 deletions magni_demos/launch/simple_navigation_flat.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<!--
This launch file brings up a simple navigation system using fiducials [1]
and move_basic [2].

[1] http://wiki.ros.org/fiducials
[2] http://wiki.ros.org/move_basic
-->
<launch>
<!--
This parameter is used to specify what level of capabilites
the robot should have after this launch file.

Possible values are 'core', 'teleop', and 'navigation'

Since this launch brings up enough to do navigation,
we set it to 'navigation'.
-->
<param name="ubiquity_robot_mode" type="string" value="navigation"/>

<include file="$(find magni_nav)/launch/move_basic.launch" />
<include file="$(find magni_nav)/launch/aruco_navigation_flat.launch" />
</launch>

2 changes: 1 addition & 1 deletion magni_description/urdf/magni.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@
</xacro:if>
<xacro:if value="${raspicam_mount == 'upward'}">
<xacro:raspi_camera name="raspicam" connected_to="base_link">
<origin xyz="0.035 0.15 0.14" rpy="0 0 ${pi}"/>
<origin xyz="0.020 0.115 0.16" rpy="0 0 ${pi}"/>
</xacro:raspi_camera>
</xacro:if>
</xacro:if>
Expand Down
17 changes: 15 additions & 2 deletions magni_nav/launch/aruco.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,11 @@
-->
<launch>
<arg name="mapping_mode" default="false"/>
<arg name="fiducial_len" default="0.14"/>
<arg name="read_only_map" default="false"/>
<arg name="navigate_flat" default="false"/>
<arg name="fiducials_flat" default="false"/>
<arg name="verbose_info" default="false"/>

<!-- camera -->
<include file="$(find raspicam_node)/launch/camerav2_1280x960_10fps.launch" />
Expand All @@ -12,9 +17,10 @@
<arg name="camera" value="/raspicam_node"/>
<arg name="image" value="image"/>
<arg name="transport" value="compressed"/>

<arg name="verbose_info" value="$(arg verbose_info)"/>

<!-- fiducial_len -->
<arg name="fiducial_len" value="0.140" />
<arg name="fiducial_len" value="$(arg fiducial_len)"/>
</include>

<!-- Fiducial slam -->
Expand All @@ -23,5 +29,12 @@
<arg name="odom_frame" value="odom"/>
<arg name="base_frame" value="base_footprint"/>
<arg name="future_date_transforms" value="0.5"/>
<arg name="verbose_info" value="$(arg verbose_info)"/>
<arg name="fiducials_flat" value="$(arg fiducials_flat)"/>
<arg name="read_only_map" value="$(arg read_only_map)"/>
<arg name="navigate_flat" value="$(arg navigate_flat)"/>

<!-- fiducial_len -->
<arg name="fiducial_len" value="$(arg fiducial_len)"/>
</include>
</launch>
33 changes: 33 additions & 0 deletions magni_nav/launch/aruco_nav_map_flat.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<!--
Run the 3d fiducial localization for Nav2D flat floor navigation method
A special mode that removes roll and pitch from fiducials used for mapping is enabled
-->
<launch>
<arg name="mapping_mode" default="false"/>
<arg name="fiducial_len" default="0.11"/>
<arg name="verbose_info" default="true"/>

<!-- camera -->
<include file="$(find raspicam_node)/launch/arducam2p3mm_1296x972_10fps.launch" />

<!-- Fiducial detection -->
<include file="$(find aruco_detect)/launch/aruco_detect.launch">
<arg name="camera" value="/raspicam_node"/>
<arg name="image" value="image"/>
<arg name="transport" value="compressed"/>
<arg name="fiducial_len" value="$(arg fiducial_len)"/>
<arg name="verbose_info" value="$(arg verbose_info)"/>
</include>

<!-- Fiducial Navigation For Flat Floor -->
<include file="$(find fiducial_slam)/launch/fiducial_slam.launch">
<arg name="map_frame" value="map"/>
<arg name="odom_frame" value="odom"/>
<arg name="base_frame" value="base_link"/>
<arg name="fiducial_len" value="$(arg fiducial_len)"/>
<arg name="verbose_info" value="$(arg verbose_info)"/>
<arg name="read_only_map" value="false"/>
<arg name="navigate_flat" value="false"/>
<arg name="fiducials_flat" value="true"/>
</include>
</launch>
32 changes: 32 additions & 0 deletions magni_nav/launch/aruco_navigation_flat.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<!--
Run the 3d fiducial localization for Nav2D flat floor navigation method
This navigation method treats the map.txt file as read only so cannot grow fiducial map.
-->
<launch>
<arg name="mapping_mode" default="false"/>
<arg name="fiducial_len" default="0.14"/>
<arg name="verbose_info" default="true"/>

<!-- camera -->
<include file="$(find raspicam_node)/launch/camerav2_1280x960_10fps.launch" />

<!-- Fiducial detection -->
<include file="$(find aruco_detect)/launch/aruco_detect.launch">
<arg name="camera" value="/raspicam_node"/>
<arg name="image" value="image"/>
<arg name="transport" value="compressed"/>
<arg name="fiducial_len" value="$(arg fiducial_len)"/>
<arg name="verbose_info" value="$(arg verbose_info)"/>
</include>

<!-- Fiducial Navigation For Flat Floor -->
<include file="$(find fiducial_slam)/launch/fiducial_slam.launch">
<arg name="map_frame" value="map"/>
<arg name="odom_frame" value="odom"/>
<arg name="base_frame" value="base_link"/>
<arg name="fiducial_len" value="$(arg fiducial_len)"/>
<arg name="verbose_info" value="$(arg verbose_info)"/>
<arg name="read_only_map" value="true"/>
<arg name="navigate_flat" value="true"/>
</include>
</launch>
8 changes: 8 additions & 0 deletions magni_nav/launch/move_basic.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,14 @@
<param name="robot_front_length" value="0.1"/>
<param name="robot_back_length" value="0.32"/>

<!-- speed controls -->
<param name="max_linear_velocity" value="0.5"/>
<param name="max_angular_velocity" value="1.0"/>

<!-- End position tolerance -->
<param name="linear_tolerance" value="0.03"/>
<param name="angular_tolerance" value="0.01"/>

<!-- lateral control -->
<param name="min_side_dist" value="0.3"/>
<param name="max_side_dist" value="2"/>
Expand Down