added localization with nav_amcl
authorHenrique Scharlau Coelho <henriquescharlaucoelho@gmail.com>
Wed, 1 Nov 2023 00:38:22 +0000 (21:38 -0300)
committerHenrique Scharlau Coelho <henriquescharlaucoelho@gmail.com>
Wed, 1 Nov 2023 00:38:22 +0000 (21:38 -0300)
the depthimage_to_laserscan node was used to convert the depth image to
to a scan msg for the amcl node

twil_2dnav/config/amcl_params.yaml [new file with mode: 0644]
twil_2dnav/config/ekf.yaml [deleted file]
twil_2dnav/config/ekf_params.yaml [new file with mode: 0644]
twil_2dnav/config/twil_2dnav.rviz
twil_2dnav/launch/nav2_navigator.launch.xml

diff --git a/twil_2dnav/config/amcl_params.yaml b/twil_2dnav/config/amcl_params.yaml
new file mode 100644 (file)
index 0000000..0b6407a
--- /dev/null
@@ -0,0 +1,14 @@
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    base_frame_id: "twil_origin"
+    global_frame_id: "map"
+    odom_frame_id: "odom"
+    tf_broadcast: true
+    scan_topic: camera/depth/image_scan
+    set_initial_pose: True
+    initial_pose: 
+      x: 0.0
+      y: 0.0
+      z: 0.0
+      yaw: 0.0
diff --git a/twil_2dnav/config/ekf.yaml b/twil_2dnav/config/ekf.yaml
deleted file mode 100644 (file)
index 91d4bc6..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-### ekf config file ###
-ekf_filter_node:
-    ros__parameters:
-# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin
-# computation until it receives at least one message from one of theinputs. It will then run continuously at the
-# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.
-        frequency: 30.0
-
-# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is
-# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar
-# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected
-# by, for example, an IMU. Defaults to false if unspecified.
-        two_d_mode: true
-
-# Whether to publish the acceleration state. Defaults to false if unspecified.
-        publish_acceleration: true
-
-# Whether to broadcast the transformation over the /tf topic. Defaultsto true if unspecified.
-        publish_tf: false
-
-# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
-#     1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of odom_frame.
-# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set "world_frame"
-#    to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes.
-# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark
-#    observations) then:
-#     3a. Set your "world_frame" to your map_frame value
-#     3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state estimation node
-#         from robot_localization! However, that instance should *not* fuse the global data.
-        map_frame: map              # Defaults to "map" if unspecified
-        odom_frame: odom            # Defaults to "odom" if unspecified
-        base_link_frame: twil_origin  # Defaults to "base_link" ifunspecified
-        world_frame: odom           # Defaults to the value ofodom_frame if unspecified
-
-        #odom0 topic is set on launch file
-        odom0_config: [true, true, false,
-                       false, false, false,
-                       false, false, false,
-                       false, false, true,
-                       false, false, false]
-
-        imu0: sensor/imu
-        imu0_config: [false, false, false,
-                      false, false, true,
-                      false, false, false,
-                      false, false, true,
-                      true, false, false]
\ No newline at end of file
diff --git a/twil_2dnav/config/ekf_params.yaml b/twil_2dnav/config/ekf_params.yaml
new file mode 100644 (file)
index 0000000..59ebd3d
--- /dev/null
@@ -0,0 +1,23 @@
+ekf_filter_node:
+    ros__parameters:
+        frequency: 30.0
+        two_d_mode: true
+        publish_acceleration: true # Whether to publish the acceleration state. Defaults to false if unspecified.
+        publish_tf: false # atualmente a tf é publicado pelo twist_mrac e não tem parametro para desativar
+        map_frame: map
+        odom_frame: odom
+        base_link_frame: twil_origin
+        world_frame: odom
+        # config order: (X,Y,Z,roll,pitch,yaw,X˙,Y˙,Z˙,roll˙,pitch˙,yaw˙,X¨,Y¨,Z¨)
+        # odom0 topic is set on launch file
+        odom0_config: [true,  true,  true,
+                       false, false, false,
+                       false, false, false,
+                       false, false, true,
+                       false, false, false]
+        imu0: sensor/imu
+        imu0_config: [false, false, false,
+                      true,  true,  true,
+                      false, false, false,
+                      false, false, false,
+                      false, false, false]
\ No newline at end of file
index 2e9a6e3..9a141ab 100644 (file)
@@ -8,6 +8,7 @@ Panels:
         - /Odometry1
         - /Global Plan1/Topic1
         - /Camera Color1/Visibility1
+        - /LaserScan1
       Splitter Ratio: 0.570588231086731
     Tree Height: 189
   - Class: rviz_common/Selection
@@ -532,6 +533,7 @@ Visualization Manager:
         Global Plan: false
         Grid: true
         Ground Truth: false
+        LaserScan: true
         Local Costmap: false
         Local Plan: false
         Map: false
@@ -563,6 +565,7 @@ Visualization Manager:
         Global Plan: false
         Grid: true
         Ground Truth: false
+        LaserScan: true
         Local Costmap: false
         Local Plan: false
         Map: false
@@ -609,6 +612,40 @@ Visualization Manager:
       Use Fixed Frame: true
       Use rainbow: true
       Value: true
+    - Alpha: 1
+      Autocompute Intensity Bounds: true
+      Autocompute Value Bounds:
+        Max Value: 10
+        Min Value: -10
+        Value: true
+      Axis: Z
+      Channel Name: intensity
+      Class: rviz_default_plugins/LaserScan
+      Color: 255; 255; 0
+      Color Transformer: FlatColor
+      Decay Time: 0
+      Enabled: true
+      Invert Rainbow: false
+      Max Color: 255; 255; 255
+      Max Intensity: 4096
+      Min Color: 0; 0; 0
+      Min Intensity: 0
+      Name: LaserScan
+      Position Transformer: XYZ
+      Selectable: true
+      Size (Pixels): 3
+      Size (m): 0.10000000149011612
+      Style: Flat Squares
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        Filter size: 10
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: /camera/depth/image_scan
+      Use Fixed Frame: true
+      Use rainbow: false
+      Value: true
   Enabled: true
   Global Options:
     Background Color: 48; 48; 48
@@ -654,26 +691,21 @@ Visualization Manager:
   Value: true
   Views:
     Current:
-      Class: rviz_default_plugins/Orbit
-      Distance: 26.927026748657227
+      Angle: 0
+      Class: rviz_default_plugins/TopDownOrtho
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.05999999865889549
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
-      Focal Point:
-        X: 0.0057085235603153706
-        Y: 4.187395095825195
-        Z: 6.038466930389404
-      Focal Shape Fixed Size: true
-      Focal Shape Size: 0.05000000074505806
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.009999999776482582
-      Pitch: 0.735398530960083
-      Target Frame: <Fixed Frame>
-      Value: Orbit (rviz)
-      Yaw: 4.70857572555542
+      Scale: 41.62940216064453
+      Target Frame: twil_origin
+      Value: TopDownOrtho (rviz_default_plugins)
+      X: 0.8133240938186646
+      Y: 0.01098377350717783
     Saved: ~
 Window Geometry:
   Camera Color:
index 6e67166..0cf56b3 100644 (file)
@@ -30,8 +30,6 @@
         <param name="yaml_filename" value="$(var map)"/>
     </node>
 
-    <node pkg="tf2_ros" exec="static_transform_publisher" name="odom_frame_publisher" args="--frame-id map --child-frame-id odom"/>
-
     <node pkg="nav2_controller" exec="controller_server" name="controller_server">
         <param name="use_sim_time" value="$(var use_sim_time)"/>
         <param from="$(find-pkg-share twil_2dnav)/config/controller_params.yaml"/>
         <remap from="odom" to="$(var controller)/odom"/>
     </node>
 
+    <node pkg="nav2_amcl" exec="amcl" name="amcl">
+        <param name="use_sim_time" value="$(var use_sim_time)"/>
+        <param from="$(find-pkg-share twil_2dnav)/config/amcl_params.yaml"/>
+    </node>
+
     <node pkg="nav2_lifecycle_manager" exec="lifecycle_manager" name="lifecycle_manager_nav2">
         <param name="use_sim_time" value="$(var use_sim_time)"/>
         <param name="autostart" value="$(var autostart)"/>
         <param name="node_names" value="[
             'map_server',
+            'amcl',
                        'controller_server',
                        'planner_server',
                        'behavior_server',
     <node pkg="robot_localization" exec="ekf_node" name="ekf_filter_node" output="screen">
         <param name="use_sim_time" value="$(var use_sim_time)"/>
         <param name="odom0" value="$(var controller)/odom"/>
-        <param from="$(find-pkg-share twil_2dnav)/config/ekf.yaml"/>
+        <param from="$(find-pkg-share twil_2dnav)/config/ekf_params.yaml"/>
+    </node>
+
+    <node name="depthimage_to_laserscan" pkg="depthimage_to_laserscan" exec="depthimage_to_laserscan_node">
+        <remap from="depth" to="/camera/depth/image_raw"/> 
+        <remap from="depth_camera_info" to="/camera/depth/camera_info"/> 
+        <remap from="scan" to="/camera/depth/image_scan"/> 
+        <param name="output_frame" type="str" value="camera_link"/> 
     </node>
 
 </launch>