Giter Site home page Giter Site logo

iris_lama_ros's Introduction

LaMa ROS - Alternative Localization and Mapping for ROS.

https://github.com/iris-ua/iris_lama_ros

Build Melodic

Developed and maintained by Eurico Pedrosa, University of Aveiro (C) 2019.

Overview

ROS integration of LaMa, a Localization and Mapping package from the Intelligent Robotics and Systems (IRIS) Laboratory, University of Aveiro. It provides 2D Localization and SLAM. It works great on a TurtleBot2 with a Raspberry Pi 3 Model B+ and an Hokuyo (Rapid URG).

Build

To build LaMa ROS, clone it from GitHub and use catkin to build.

mkdir src
cd src
git clone https://github.com/iris-ua/iris_lama
git clone https://github.com/iris-ua/iris_lama_ros
cd ..
catkin config --extend /opt/ros/noetic
catkin build

The build was tested in Ubuntu 20.04 with ROS noetic. It will not build with catkin_make or catkin_make_isolated.

SLAM nodes

To create a map using Online SLAM execute

rosrun iris_lama_ros slam2d_ros scan_topic:=base_scan

and to create a map using Particle Filter SLAM execute

rosrun iris_lama_ros pf_slam2d_ros scan_topic:=base_scan

and to create a map using Graph SLAM execute

rosrun iris_lama_ros graph_slam2d_ros scan_topic:=base_scan

All nodes will publish to expected topics such as /map and /tf.

Offline Mapping (rosbag)

If you want to obtain a map from a rosbag and you want to save time (a lot), you can let iris_lama_ros "play" the rosbag for you.

roslaunch iris_lama_ros slam2d_offine.launch scan_topic:=base_scan rosbag:=/path/your/rosbag.bag

or

roslaunch iris_lama_ros pf_slam2d_offine.launch scan_topic:=base_scan rosbag:=/path/your/rosbag.bag

Parameters

  • ~global_frame_id: The frame attached to the map (default: "map").
  • ~odom_frame_id: The frame attached to the odometry system (default: "odom").
  • ~base_frame_id: The frame attached to the mobile base (default: "base_link").
  • ~scan_topic: Laser scan topic to subscribe (default: "/scan").
  • ~transform_tolerance: Defines how long map->odom transform is good for by future dating tf (default: 0.1)
  • ~initial_pos_x: Initial x position (default: 0 meters).
  • ~initial_pos_y: Initial y position (default: 0 meters).
  • ~initial_pos_a: Initial rotation (or angle) (default: 0 rad).
  • ~d_thresh: Traveled distance to accumulate before updating (default: 0.01 meters).
  • ~a_thresh: Angular motion to accumulate before updating (default: 0.25 rads).
  • ~l2_max: Maximum distance to use in the dynamic Euclidean distance map (default: 0.5 meters).
  • ~resolution: Resolution of the grid maps (default: 0.05 meters).
  • ~patch_size: Length of a patch (default: 32 cells).
  • ~strategy: Scan matching optimization strategy, GaussNewton ("gm") or Levenberg Marquard ("lm") (default: "gn").
  • ~max_iterations: Maximum number of iterations performed by the optimizer (default: 100)
  • ~use_compression: Should the maps be compressed (default: false).
  • ~compression_algorithm: Compression algorithm to use, lz4 or zstd (default: "lz4").
  • ~cache_size: Size of the LRU used during online data compression (default: 100).
  • ~mrange: Maximum laser scan range (default: 16 meters).
  • ~beam_step: Number of beams to step (or skip) in each scan (default: 1).
  • ~truncate: Truncate the laser scan range from start to "middle" (default: 0.0 meters, 0.0 means no truncation).
  • ~truncate_ray: Truncate the laser scan range (or ray) from "middle" to end (default: 0.0 meters, 0.0 means no truncation).
  • ~map_publish_period: How long between updates to the map (default: 5 seconds).
  • ~transient_map: True to only keep the most recent portion of the map "sensed" by the latest surface (default": false)
  • ~create_summary: (default: false)

Particle Filter SLAM only:

  • ~d_thresh: Traveled distance to accumulate before updating (default: 0.5 meters).
  • ~particles: Number of particles to use (default: 30).
  • ~seed: RNG seed value, use 0 for a random seed from device (default: 0)
  • ~threads: Number of working threads, -1 means disabled and 0 will expand to the available number of cores (default: -1).
  • ~sigma: Measurement variance (default: 0.05).
  • ~lgain: Gain value for smoothing the particles likelihood (default: 3.0).
  • ~srr: Odometry error in rotation as a function of rotation (default: 0.1).
  • ~str: Odometry error in rotation as a function of translation (default: 0.2).
  • ~stt: Odometry error in translation as a function of translation (default: 0.1).
  • ~srt: Odometry error in translation as a function of rotation (default: 0.1).

Graph SLAM only:

  • ~d_thresh: Traveled distance to accumulate before updating (default: 0.25 meters).
  • ~key_pose_distance: Traveled distance to accumulate before creating a key pose (default: 0.5)
  • ~key_pose_angular: Angular motion to accumulate before creating a key pose (default: PI/2)
  • ~key_pose_head_delay: Number of latest key poses to ignore for head key pose reference (default: 3)
  • ~loop_search_max_distance: Maximum distance used in the adaptive search of a loop candidate (default: 15.0)
  • ~loop_search_min_distance: Mininum distance used in the adaptive search of a loop candidate (default: 5.0)
  • -loop_closure_scan_rmse: Maximum RMSE (root mean-squared-error) allowed for a loop candidate (default: 0.075). Increase this value if loop closure links are not being created properly. A good value would be 0.1. Beware of false positives when this value too high.
  • ~loop_max_candidates: Maximum number of candidates considered for loop closure (default: 5)
  • ~ignore_n_chain_poses: Number of the lastest key poses to ignore for loop closure (default: 20)

Services

  • /dynamic_map:

Localization node

This node requires the existence of the /static_map service to load the map. To run the localization just execute

rosrun iris_lama_ros loc2d_ros scan:=base_scan

Please use rviz to set the initial pose. Global localization is not yet implemented.

Services

  • /request_nomotion_update: Called to trigger an update without moving the robot (no-motion update)
  • /global_localization: Called to trigger a global localization procedure.

Parameters

  • ~global_frame_id: The frame attached to the map (default: "map").
  • ~odom_frame_id: The frame attached to the odometry system (default: "odometry").
  • ~base_frame_id: The frame attached to the mobile base (default: "base_link").
  • ~scan_topic: Laser scan topic to subscribe (default: "/scan").
  • ~mrange: Maximum laser scan range. When 0, maximum range defaults to the sensor maximum range. (default: 0 meters).
  • ~transform_tolerance: Defines how long map->odom transform is good for by future dating tf (default: 0.1)
  • ~temporal_update: Force an update if the last processed scan is older than this. A value less or equal to zero disables the check (default: 0.0).
  • ~publish_tf: Publish TF correction from global_frame_id to odom_frame_id (default: true).
  • ~beam_step: Number of beams to step (or skip) in each scan (default: 1).
  • ~initial_pos_x: Initial x position (default: 0 meters).
  • ~initial_pos_y: Initial y position (default: 0 meters).
  • ~initial_pos_a: Initial rotation (or angle) (default: 0 rad).
  • ~d_thresh: Traveled distance to accumulate before updating (default: 0.01 meters).
  • ~a_thresh: Angular motion to accumulate before updating (default: 0.2 rads).
  • ~l2_max: Maximum distance to use in the dynamic Euclidean distance map (default: 0.5 meters).
  • ~strategy: Scan matching optimization strategy, GaussNewton ("gm") or Levenberg Marquard ("lm") (default: "gn").
  • ~patch_size: Length of a patch (default: 32 cells).
  • ~covariance_blend: Blending factor ([0,1]) between optimization covariance and sampling covariance (default: 0.0).
  • ~use_map_topic: True to subscribe to the /map topic instead of requesting the map through the "static_map" service (default: false).
  • ~first_map_only: True to use only the first map ever received (default: false).
  • ~use_pose_on_new_map: True to use the current algorithm pose when the map changes (default: false).
  • ~force_update_on_initial_pose: True to trigger a no-motion update when an initial pose is received (default: false)
  • ~gloc_particles: Number of particles used to find the best global localization (default: 3000)
  • ~gloc_thresh: Value at which a global localization particle is considered viable. (default: 0.15 RMSE)
  • ~gloc_iters: Maximum number of iterations executed by the global localization procedure (default: 20)
  • ~do_global_loc: True to trigger an initial global localization (default: false)

iris_lama_ros's People

Contributors

combinacijus avatar cosmicog avatar efernandez avatar eupedrosa avatar facontidavide avatar jcmonteiro avatar msadowski avatar silviis avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar

iris_lama_ros's Issues

Laser has to be mounted planar! Z-coordinate has to be 1 or -1

I tried to use loc2d_ros(dashing-devel) with TurtleBot3(Gazebo).
https://github.com/atinfinity/turtlebot3_lama_ros2

$ ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py
$ ros2 launch turtlebot3_lama_navigation turtlebot3_lama_navigation.py

But, the following message was displayed.

[loc2d_ros-1] [WARN] [iris_lama_ros2.loc2d_ros]: Laser has to be mounted planar! Z-coordinate has to be 1 or -1, but gave: 1.12200

And, I found the following comment.
https://github.com/iris-ua/iris_lama_ros/blob/dashing-devel/start.sh#L32-L34

TB3 doesnt have a planar sensor, so you need to uncomment line 336 of loc2d_ros.cpp and rebuild

So, I uncomment this line. As a result, it works fine.

Galactic support

Is this node supported on galactic and the current nav2 version?

Reconstructing a map in offline mode might produce incorrect maps

I have noticed that the map that I obtain when running the algorithm in the robot in real-time is always better than the one that I get from replaying the ROS bag and running the offline node, e.g., see #21.

I concluded that this is because the messages are published too fast by the ReplayRosbag function for the algorithm to consume them. Increasing the queue as suggested in #21 and enabling TCP_NODELAY as suggested in #22 help mitigate the issue, but it still doesn't go away. To check that this inference is right, I have reduced the rate from 5 kHz to 30 Hz

ros::WallRate rate(5000); // 5Mhz
matching the rate on the real system, and producing maps that are exactly the same and exactly the same as the one generated in real-time.

My suggestion then is to change the offline node to use https://github.com/iris-ua/iris_lama as library directly, without publishing and subscribing to topics, thus ensuring that no messages will be lost. I can maybe do this in a week or so if I get some spare time.

Transforming Maps Issue

Hi,

Thanks for this amazing pkg. It truly is remarkable.

I have an issue im struggling with and was wondering perhaps you might have some insight into.
This is most probably not an issue with lama itself but rather something i am doing wrong, and also i have a work around for it but was hoping to learn from this issue and maybe perhaps others who read this would too.

The issue:
I used slam2d_offline to generate a map. The generated map is great but the origin of the map is set at the initial pose of the robot where the recorded bag started. However, the rest of the robot works in a different global frame (called 'world') and so in-order for me to use lama's pose estimation i needed to setup a static transformer from lama's frame to 'world' frame. I was able to find the transformation from the map's origin to world's origin and used a static transformer to transform lama's pose to the world pose. In this setup everything works great.
However, I wanted to avoid using a static transformer altogether by moving the map's origin (the one that was obtained through slam2d_offline) directly to my world origin. to do this, i simply set up a small python node and used tf2 to calculate the world origin w.r.t the pgm file's origin which is the left most bottom pixel. I then moved the origin of the map to the world's origin by resetting the "origin" field in the accompanying yaml to the pgm image to be that of the world frame.

When i do this, for some reason, lama's pose gets skewed over time (of course i also drop the code that transform lama's pose to world since now 'map' frame is the same 'world')

I'll note that in both cases, i use the '/initialpose' topic to force the starting position of the robot from a known position due to the fact that the robot does not always start at 0,0 in the map's frame.

Maybe you have some insight as to why this is happening?

Some technical data:

Works great:
slam map frame origin (as given by slam2d_offline):
origin: [-11.200000, -5.600000, 0.000000]
^ this origin is w.r.t. pgm left most bottom pixel

static transformation from slam map origin to world origin:

Then transform lama's pose to world. this works great. but feels like taking extra steps.

Gets skewed overtime:
slam map frame origin after calculating world origin w.r.t pgm left most bottom pixel:
origin: [-1.645762293,25.6100276713,-1.55481620315]

Then i only use 'map' frame because there is no need for 'world' frame.

What could be causing lama's pose to skew?

tl;dr
Using a static transformer to transform lama's pose to a world pose works great.
However changing the map's origin to be that of world's origin and dropping the static transformer produces skewed results.
The origin transformation is 100% correct, what could be the issue?

Thanks for reading.

Allow compilation in Kinetic

Hi,

I am trying to compile in Kinetic. A couple of changes to make it easier for everybody:

  • lower minimum CMAKE requirement to 3.5 (including repository iris_lama)
  • add set(CMAKE_CXX_STANDARD 11) to CMakeLists.txt iris_lama_ros.

Black Dots Randomly Jumping On Map Without Lidar Feedback

The Setup

  • Ubuntu 20.04
  • ROS noetic
  • 2x Hokuyo Lidars Mounted upside down in the robot
    <xacro:macro name="hokuyo_plugin" params="name topic">
    <!-- hokuyo -->
    <gazebo reference="$(arg tf_prefix)_${name}_frame">
      <sensor type="ray" name="$(arg tf_prefix)_${name}_sensor">
        <pose>0 0 0 0 0 0</pose>
        <visualize>true</visualize>
        <update_rate>20</update_rate>
        <ray>
          <scan>
            <horizontal>
              <samples>720</samples>
              <resolution>1</resolution>
              <min_angle>-${2*PI*102.5/360}</min_angle>
              <max_angle>${2*PI*130/360}</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.05</min>
            <max>30.0</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <!-- Noise parameters based on published spec for Hokuyo laser
                achieving "+-30mm" accuracy at range < 10m.  A mean of 0.0m and
                stddev of 0.01m will put 99.7% of samples within 0.03m of the true
                reading. -->
            <mean>0.0</mean>
            <stddev>0.001</stddev>
          </noise>
        </ray>
        <plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_laser.so">
          <topicName>/$(arg skidname)/${topic}</topicName>
          <frameName>$(arg tf_prefix)_${topic}_frame</frameName>
        </plugin>
      </sensor>
    </gazebo>
    </xacro:macro>
    
  • Gazebo 11

How to reproduce

  1. Start a gazebo world with objects
  2. Start iris_lama slam_2d
  3. Move an object in gazebo that already has been identified as static wall

Actual Behavior

On this screenshot you can see black dots around the footprint of the robot on the right hand side of the screenshot.

  • Those do not exist in the simulation and still make the robot think he is stuck.
  • No lidar points appeared where the dots appear (at least not the last 10 minutes, but at the beginning the obstacle on the left side of the screenshot was there)
  • The dots behavior remind of Conway's Game of Life
    image

Note: We observe the same behavior on the real robot, in the real word with sick nanoscan3 lidars.

Expected Behavior

  • Map contains static obstacles only at places where lidar points appear
  • Dots do not appear in free space without lidar point event
  • When formerly static objects start to disappear on the map, they should fully disappear and not leave some blinking dots behind

Fixed Frame [map] does not exist - is LaMa localization node supposed to publish /map --> /odom ?

Hi!
Firstly, thanks for providing such great SLAM / Localization work.

I was trying to implement the localization function of LaMa ROS based on my own occupancy grid map. I launched the command lines in different windows in the following order:

  1. rosrun iris_lama_ros loc2d_ros scan:=base_scan
  2. rosrun map_server map_server /opt/ros/kinetic/share/husky_navigation/maps/mymap.yaml
  3. rviz
  4. rosbag play --clock /home/williamwoo/Z_husky_S2.1/S2.1_new/husky2-pose-_2020-06-12-s2.1-way11-mrpt.bag

The map is successfully loaded, where in the command line saying that:

[ INFO] [1606198756.368682224]: Requesting the map...
[ INFO] [1606198761.232647620, 1592210365.736253594]: Localization parameters: d_thresh: 0.01, a_thresh: 0.20, l2_max: 0.50
[ INFO] [1606198761.454955949, 1592210365.938106792]: 2D Localization node up and running

I suppose the localization node is successfully running. However, there is an error saying that Fixed Frame [map] does not exist (as shown below).
rviz

The tf is:
way11-test-tf-tree

The rosbag info is:
way11-test-rosbag-info

So I'm wondering how could I solve this problem? I suppose what the LaMa ROS localization node does is to publish /map --> /odom, right?
The map that I used is mymap.yaml and mymap.pgm; the rosbag that I used is here.

Thanks and all the best!

Best Regards,
William

Cant compile on Raspberry Pi - Noetic

Hey @eupedrosa, i have a problem compiling iris on rpi4, heres what im doing:

Raspberry pi 4 rev 1.4

ubuntu@pi-focal:~/iris_slam_ws/src$ ls
iris_lama  iris_lama_ros
ubuntu@pi-focal:~/iris_slam_ws/src/iris_lama_ros$ git checkout noetic-devel
ubuntu@pi-focal:~/iris_slam_ws/src/iris_lama$ git status
On branch master
ubuntu@pi-focal:~/iris_slam_ws$ catkin config --extend /opt/ros/noetic
ubuntu@pi-focal:~/iris_slam_ws$ rosdep install --from-paths src --ignore-src -r -y
#All required rosdeps installed successfully
ubuntu@pi-focal:~/iris_slam_ws$ catkin build
...              
_____________________________________________________________________________________________________
Errors     << iris_lama:make /home/ubuntu/iris_ws/logs/iris_lama/build.make.000.log                  
/home/ubuntu/iris_ws/src/iris_lama/src/loc2d.cpp: In member function ‘void lama::Loc2D::addSamplingCovariance(const Ptr&)’:
/home/ubuntu/iris_ws/src/iris_lama/src/loc2d.cpp:211:55: error: no matching function for call to ‘max(unsigned int, long unsigned int)’
  211 |     const size_t step = std::max(num_points / 100, 1ul);

Error: TF NAN_INPUT

I ran loc2d with navigation2 on Ubuntu 20.04 and foxy, in some cases it works.

But in many cases, I got the following errors:

[loc2d_ros-4] Error:   TF NAN_INPUT: Ignoring transform for child_frame_id "odom" from authority "Authority undetectable" because of a nan value in the transform (-nan -nan -nan) (0.000685 0.000360 -0.000007 1.000000)
[loc2d_ros-4]          at line 278 in /tmp/binarydeb/ros-foxy-tf2-0.13.10/src/buffer_core.cpp
[rviz2-3] Error:   TF NAN_INPUT: Ignoring transform for child_frame_id "odom" from authority "Authority undetectable" because of a nan value in the transform (-nan -nan -nan) (0.000685 0.000360 -0.000007 1.000000)
[rviz2-3]          at line 278 in /tmp/binarydeb/ros-foxy-tf2-0.13.10/src/buffer_core.cpp
[recoveries_server-9] Error:   TF NAN_INPUT: Ignoring transform for child_frame_id "odom" from authority "Authority undetectable" because of a nan value in the transform (-nan -nan -nan) (0.000685 0.000360 -0.000007 1.000000)
[recoveries_server-9]          at line 278 in /tmp/binarydeb/ros-foxy-tf2-0.13.10/src/buffer_core.cpp
[bt_navigator-10] Error:   TF NAN_INPUT: Ignoring transform for child_frame_id "odom" from authority "Authority undetectable" because of a nan value in the transform (-nan -nan -nan) (0.000685 0.000360 -0.000007 1.000000)
[bt_navigator-10]          at line 278 in /tmp/binarydeb/ros-foxy-tf2-0.13.10/src/buffer_core.cpp
[controller_server-7] Error:   TF NAN_INPUT: Ignoring transform for child_frame_id "odom" from authority "Authority undetectable" because of a nan value in the transform (-nan -nan -nan) (0.000685 0.000360 -0.000007 1.000000)
[controller_server-7]          at line 278 in /tmp/binarydeb/ros-foxy-tf2-0.13.10/src/buffer_core.cpp
[planner_server-8] Error:   TF NAN_INPUT: Ignoring transform for child_frame_id "odom" from authority "Authority undetectable" because of a nan value in the transform (-nan -nan -nan) (0.000685 0.000360 -0.000007 1.000000)
[planner_server-8]          at line 278 in /tmp/binarydeb/ros-foxy-tf2-0.13.10/src/buffer_core.cpp

I use the same launch tb3_simulation_launch.py in navigation2 except replacing amcl with loc2d.

How to cite this method?

Hi, I am interested in using the localization method in my research, but I need an article where the method is described in order to cite it correctly. I have found one titled "Efficient localization based on scan matching with a continuous likelihood field" by Eurico Pedrosa et al, published in ICARSC 2017, but I am not sure if the method described in that paper is the same one implemented here or if the method is published in another paper. Can someone clarify it for me?

Suggestion: time based update

Hi!

First of all I would like to say that I'm very pleased with this library. We previously used gmapping on our mobile robot, but I found this package, tried it, and was blown away, because it seems to be better than gmapping in about every way. Also, loc2d works better than amcl for me as well. ROS integration is great too. So thanks for sharing this amazing software. I really think this should be the default mapping and localization in ROS.

On to my suggestion. I think it would be really useful to have time based updates for localization (maybe mapping too), kindof like gmapping's "temporalUpdate" parameter. So it would be possible to have a fixed frequency updating of the position even if the robot isn't moving based on the odometry. I know I could just call the "request_nomotion_update" service, but it would be nice to have a built-in option to do this periodically.

I think this won't be too difficult to do, so is there anything I'm missing here? Maybe there is some reason this is not already an option? Or do you think it wouldn't be useful?

Thanks

Optionally disable map->odom tf transfrom

I would propose to add a parameter to optionally disable publishing of map->odom tf transfrom, such as tf_broadcast parameter in amcl package.

Use case for this is when one would be using robot_localization package for fusing multiple localization sources with Kalman filter (e.g localization with lama + bluetooth beacons or GPS). In this case map->odom is (or can be) published by robot_localization nodes and should be disabled for robot_localization input sources, i.e lama ros.

Edit: I see that using Kalman filter is also discussed in #5.

covariance of position

Hi,
I am working with this package.
How can I know the covariance of the solution?
Thanks

How can iris_lama be automatically linked with ROS2 'colcon' tool?

How can the iris_lama package be automatically linked, when using colcon to build the ROS2 port of iris_lama_ros?

My current approach is to copy header files into the include/lama folder, and building iris_lama.a to put into the src directory. This works, but is not very portable. Is there a way to automate this, and build both packages automatically? This has some information about exporting a package, but I was unable to get it working.

Internal compiler error when building for eloquent

I get the following error output for building iris_lama_ros2 with colcon build:

In file included from /opt/ros/eloquent/include/rclcpp/subscription_base.hpp:27:0, from /opt/ros/eloquent/include/rclcpp/callback_group.hpp:26, from /opt/ros/eloquent/include/rclcpp/any_executable.hpp:20, from /opt/ros/eloquent/include/rclcpp/memory_strategy.hpp:24, from /opt/ros/eloquent/include/rclcpp/memory_strategies.hpp:18, from /opt/ros/eloquent/include/rclcpp/executor.hpp:33, from /opt/ros/eloquent/include/rclcpp/executors/multi_threaded_executor.hpp:25, from /opt/ros/eloquent/include/rclcpp/executors.hpp:21, from /opt/ros/eloquent/include/rclcpp/rclcpp.hpp:145, from /home/mascor/turtlebot3_ws/src/iris_lama_ros/include/lama/ros/slam2d_ros.h:37, from /home/mascor/turtlebot3_ws/src/iris_lama_ros/src/slam2d_ros.cpp:34: /opt/ros/eloquent/include/rclcpp/experimental/intra_process_manager.hpp: In member function ‘void rclcpp::experimental::IntraProcessManager::do_intra_process_publish(uint64_t, std::unique_ptr<MessageT, MessageDeleter>, std::shared_ptr<typename std::allocator_traits<_Alloc>::rebind_traits<MessageT>::allocator_type>) [with MessageT = nav_msgs::msg::OccupancyGrid_<std::allocator<void> >; Alloc = std::allocator<void>; Deleter = std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >]’: /opt/ros/eloquent/include/rclcpp/experimental/intra_process_manager.hpp:237:3: internal compiler error: Segmentation fault } ^

Failure on updating map with loc2d_ros

I am loofing at loc2d_ros for replacing the amcl node.
It works quite well even with the default params.
However, the localisation will fail if I publish a new map to the map topic.
Any idea?

The ros version using is Noetic.
The params using are as below:

                    global_frame_id: "map",
                    odom_frame_id: "odom",
                    base_frame_id: "base_link",
                    scan_topic: scanTopic,
                    d_thresh: 0.1,
                    a_thresh: 0.2,
                    l2_max: 0.5,
                    strategy: "gn",
                    use_map_topic: true,
                    first_map_only: true,
                    use_pose_on_new_map: false,
                    force_update_on_initial_pose: false,

I can send you the rosbag file if needed.

ros2 launch

Hi,
I'm working with this on the eloquent devel. @bluemoon93 I see that on the dashing-devel you added 2 launch files for live slam. When I build this on eloquent it didn't pick up these launch files because launch wasn't picked up in the name (pf_slam2d_live.py). I changed this to pf_slam2d_live_launch.py and everything was fine. Did you not have this issue building on dashing?

Local costmap does not overlap with global map

irisLaMa_20221221_3


Dear Sir,

It occurs sometime a trobule that a local costmap does not overlap with the global map in the navigation by move_base using iris_LaMa.

Is this problem due to a non-convergence of iris_LaMa localization caluculation ? OR
Is its problem due to a set of parameters that are related with move_base/costmap/dwa ?

Could you like advise to solve this problem ?
I send a picture of simulation result.
Left side: gazebo
Right side: rviz

Best Regards

can not save closed loop map

hello @eupedrosa
rviz seems has detected close loop ,but the map didn't fix the drift,I used map_server to save the map,but the result still didn't fix the drift .
微信图片_20220909162605

new lidar odom compiler error

Errors << iris_lama_ros:make /home/jason/loc_ws/logs/iris_lama_ros/build.make.005.log
In file included from /home/jason/loc_ws/devel/include/lama/lidar_odometry_2d.h:36:0,
from /home/jason/loc_ws/src/iris_lama_ros/include/lama/ros/lidar_odometry2d_ros.h:55,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:37:
/home/jason/loc_ws/devel/include/lama/types.h:101:27: error: redefinition of ‘template int lama::sign(T)’
template int sign(T val) {
^~~~
In file included from /opt/ros/melodic/include/lama/image.h:38:0,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:34:
/opt/ros/melodic/include/lama/types.h:89:27: note: ‘template int lama::sign(T)’ previously declared here
template int sign(T val) {
^~~~
In file included from /home/jason/loc_ws/devel/include/lama/lidar_odometry_2d.h:36:0,
from /home/jason/loc_ws/src/iris_lama_ros/include/lama/ros/lidar_odometry2d_ros.h:55,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:37:
/home/jason/loc_ws/devel/include/lama/types.h:105:8: error: redefinition of ‘struct lama::KeyHash’
struct KeyHash {
^~~~~~~
In file included from /opt/ros/melodic/include/lama/image.h:38:0,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:34:
/opt/ros/melodic/include/lama/types.h:93:8: note: previous definition of ‘struct lama::KeyHash’
struct KeyHash {
^~~~~~~
In file included from /home/jason/loc_ws/devel/include/lama/lidar_odometry_2d.h:36:0,
from /home/jason/loc_ws/src/iris_lama_ros/include/lama/ros/lidar_odometry2d_ros.h:55,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:37:
/home/jason/loc_ws/devel/include/lama/types.h:111:8: error: redefinition of ‘struct lama::PointCloudXYZ’
struct PointCloudXYZ {
^~~~~~~~~~~~~
In file included from /opt/ros/melodic/include/lama/image.h:38:0,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:34:
/opt/ros/melodic/include/lama/types.h:99:8: note: previous definition of ‘struct lama::PointCloudXYZ’
struct PointCloudXYZ {
^~~~~~~~~~~~~
In file included from /home/jason/loc_ws/devel/include/lama/lidar_odometry_2d.h:36:0,
from /home/jason/loc_ws/src/iris_lama_ros/include/lama/ros/lidar_odometry2d_ros.h:55,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:37:
/home/jason/loc_ws/devel/include/lama/types.h:122:8: error: redefinition of ‘struct lama::PolygonMesh’
struct PolygonMesh {
^~~~~~~~~~~
In file included from /opt/ros/melodic/include/lama/image.h:38:0,
from /home/jason/loc_ws/src/iris_lama_ros/src/lidar_odometry2d_ros.cpp:34:
/opt/ros/melodic/include/lama/types.h:110:8: note: previous definition of ‘struct lama::PolygonMesh’
struct PolygonMesh {
^~~~~~~~~~~
make[2]: *** [src/CMakeFiles/lidar_odometry2d_ros.dir/lidar_odometry2d_ros.cpp.o] Error 1
make[1]: *** [src/CMakeFiles/lidar_odometry2d_ros.dir/all] Error 2

Produced map doesnt match with the Laserscan

Hi,
I just started using lama. I am trying to use the particle filter SLAM on Ros2 eloquent (Ubuntu 18.04).
My Laser is mounted upside down on the robot and there is a static transform that is taking care of this.
But Lama is producing a map, that is flipped back around and I have no idea where this is coming from.
I attach a picture, where you can see my laserscan and the map that is produced shown in rviz. It doesnt match.
The static tf should be correct. I proved it with slam_toolbox and it worked fine.
The static tf that is flipping 180° is from base_scan -> base_link.

Any idea how I could fix this?
Thanks in advance!

image

Message Filter Dropping all the messages

Hi I am trying to run Iris LAMA with YD Lidar X2L on a rapsberry pi. When I run online slam node I always get this message.

MessageFilter [target=odom ]: Dropped 100.00% of messages so far. Please turn the [ros.iris_lama_ros.message_filter] rosconsole logger to DEBUG for more information.

[DEBUG] [1629858705.451106768]: MessageFilter [target=odom ]: Removed oldest message because buffer is full, count now 100 (frame_id=laser_frame, stamp=1629858694.077876)
[DEBUG] [1629858705.451174537]: MessageFilter [target=odom ]: Added message in frame laser_frame at time 1629858705.340, count now 100

Can there be any hints on whats wrong here ?

Thanks

[signalFailure] Drop message: frame 'base_scan' at time 9.005 for reason(0)

I tried to use slam2d_ros(dashing-devel) with TurtleBot3(Gazebo).
https://github.com/atinfinity/turtlebot3_lama_ros2

But, the following message was displayed.

[slam2d_ros-1] [INFO] [iris_lama_ros2.slam2d_ros]: [signalFailure] Drop message: frame 'base_scan' at time 9.005 for reason(0)
[slam2d_ros-1] [INFO] [iris_lama_ros2.slam2d_ros]: [signalFailure] Drop message: frame 'base_scan' at time 9.206 for reason(0)

On the other hands, I changed to pf_slam2d. It works fine.

Problems on integration of localization to ros navigation stack (move-base)

First of all, I really appreciate the release of this wonderful mapping and localization package.
Currently, I'm working on an exchange amcl-based localization tool with this iris-lama-ros package.
However, when I was using this package with move base (ros navigation stack), I got the error message "Extrapolation Error: Lookup would require extrapolation into the future". (When using amcl-based localization, there was no error).
Do you have any idea to solve, or did you have any experience with such problems?
(I tried comment tf-broadcaster on localization node, but nothing changed).
It will be greatly helpful if you (or someone) can give any comments!

Question: how hard would it be to add 3D mapping and localization?

it is very nice to see haw there is a clear separation between the ROS and non ROS part in LAMA.

My question is: how mature and tested is the 3D (octomap) implementation of iris_lama? Do you see a transition to 3D SLAM with sensors such as Velodyne something very hard or relatively straightforward?

Just want your opinion before entering the white rabbit's hole myself.

Using another laserscan topic than /scan

Hi,

I am trying to get lama working with another laserscan topic than /scan.
Where do I tell the SLAM which topic is providing the laserscan data?
I am using Ros2 Eloquent on Ubuntu 18.04.

I tried to include scan_topic: scan_new and also scan_topic: /scan_new in the config file but if I do this the slam doesnt produce anything (not even a map frame) without throwing errors in the terminal.

Thanks in advance!

Large TF delay in odom to map transform

First of all, great package!

So far (in simulation) I am getting very good localization results compared to amcl on our robot.

I did notice though that the transform delay from the odom to map transform seems unusually high to me? Using tf_monitor I get about 0.4 seconds average delay from odom -> map.

In contrast, amcl seems to only have a delay of about 0.1 seconds or so. Any idea why this would be? Have other people noticed similar transform delays?

LifeLong Mapping

Hi,
If I built a map and I work with localization mode.
The area has changed and I am interested in updating the map while driving.
Is there such a possibility?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.