Coder Social home page Coder Social logo

tu-darmstadt-ros-pkg / hector_slam Goto Github PK

View Code? Open in Web Editor NEW
624.0 70.0 443.0 586 KB

hector_slam contains ROS packages related to performing SLAM in unstructed environments like those encountered in the Urban Search and Rescue (USAR) scenarios of the RoboCup Rescue competition.

Home Page: http://wiki.ros.org/hector_slam

CMake 4.55% C++ 95.45%

hector_slam's Introduction

hector_slam's People

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  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

hector_slam's Issues

When mapping without matching, updateByScan uses wrong data for higher level maps

updateByScan assumes that the dataContainers variable content matches the dataContainer that is passed to it. However, dataContainers seems to only be set in matchData. When calling HectorSlamProcessor::update with map_without_matching == true, matchData is never called. Thus, updateByScan would use old or unset containers for all but the first map level.

mapContainer[i].updateByScan(dataContainers[i-1], robotPoseWorld);

hector_compressed_map_transport ((GMAPPING))

Hello,

I am trying to use hector_compressed_map_transport for other slam algorithms too.

I know that it uses /pose. I am publishing pose by the help of http://wiki.ros.org/pose_publisher in the required msgType. But map never shows up (window freezes).

Any help please.?

I am using kinetic and trying to view the map by rosrun image_view image_view image:=/map_image/full _image_transport:=compressed (It work perfect for hector slam).

Qt version issue?

I'm trying to compile from source on ROS Melodic and the build fails since I don't have QT4. Since Ubuntu 18.04 (and therefore Melodic) uses Qt 5, how can I get this to compile?

CMake Error at /usr/share/cmake-3.10/Modules/FindQt4.cmake:1320 (message):
  Found unsuitable Qt version "" from NOTFOUND, this code requires Qt 4.x
Call Stack (most recent call first):
  hector_slam/hector_geotiff/CMakeLists.txt:12 (find_package)

problem with map updates

Hi,
I am trying to simulate a car-like robot in gazebo and to create a map of the world by using hector mapping. When I try to run hector mapping, the map is not updating, like this: https://postimg.org/image/c34oos2u9/ https://postimg.org/image/9n2vaxkrl/.
I don't get any errors and cannot figure out what is the problem.
This is my tf tree: https://postimg.org/image/yzrily0o3/.
Running roswtf ouputs:

WARNING The following node subscriptions are unconnected:
 * /hector_mapping:
   * /syscommand
 * /rviz_1472805256594766659:
   * /map_updates
 * /gazebo:
   * /gazebo/set_model_state
   * /gazebo/set_link_state

WARNING These nodes have died:
 * my_chassis/urdf_spawnermy_chassis-3

Maybe the problem is that map_updates_node of rviz is not connected?
Any suggestions how to solve the problem will be greatly appreciated.

Thanks in advance!

Hector_slam runtime error.

Hi Dear Stefan & Johannes:

I download the hector_slam for study, everything is ok, but when I run it come across a runtime error, like belows:

[ INFO] [1418181898.575329024]: Successfully initialized hector_geotiff MapWriter plugin TrajectoryMapWriter.

[ INFO] [1418181898.576077541]: Geotiff node started

hector_mapping: /usr/include/boost/smart_ptr/shared_ptr.hpp:653: typename boost::detail::sp_member_access::type boost::shared_ptr::operator->() const [with T = ros::Transport; typename boost::detail::sp_member_access::type = ros::Transport*]: Assertion `px != 0' failed.

[hector_mapping-3] process has died [pid 9617, exit code -6, cmd /home/leon/RobotSlam_ws_install/devel/lib/hector_mapping/hector_mapping __name:=hector_mapping __log:=/home/leon/.ros/log/fdf074ca-801b-11e4-8ce0-000c29387eba/hector_mapping-3.log].

log file: /home/leon/.ros/log/fdf074ca-801b-11e4-8ce0-000c29387eba/hector_mapping-3*.log
my boost version: Boost version: 1.54.0
OS version: ubuntu LTS 14.04

could you please instruct me the error? Thank you all !

Improve hector_mapping description w.r.t. odometry

The package manifest of hector_mapping (and therefore the summary on the ROS wiki page) says:

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms [...]

This does not make it clear that the mapping cannot be improved by available external odometry. I suggest changing this to

hector_mapping is a SLAM approach that does not use odometry and can be used on platforms [...]

Consolidate the default base frame name

Currently, the base_frame parameter of the package hector_mapping has got the default value base_link, while the base_frame parameter of the package hector_imu_attitude_to_tf has got the default value base_frame.

(The tutorial also inconsistently uses "base_link" in the image and "base_frame" in the configuration snippet.)

I wonder the code of OccGridMapUtil.h

`Eigen::Vector3f interpMapValueWithDerivatives(const Eigen::Vector2f& coords)
{
//check if coords are within map limits.
if (concreteGridMap->pointOutOfMapBounds(coords)){
return Eigen::Vector3f(0.0f, 0.0f, 0.0f);
}

//map coords are always positive, floor them by casting to int
Eigen::Vector2i indMin(coords.cast<int>());

//get factors for bilinear interpolation
Eigen::Vector2f factors(coords - indMin.cast<float>());

int sizeX = concreteGridMap->getSizeX();

int index = indMin[1] * sizeX + indMin[0];

// get grid values for the 4 grid points surrounding the current coords. Check cached data first, if not contained
// filter gridPoint with gaussian and store in cache.
if (!cacheMethod.containsCachedData(index, intensities[0])) {
  intensities[0] = getUnfilteredGridPoint(index);
  cacheMethod.cacheData(index, intensities[0]);
}

++index;

if (!cacheMethod.containsCachedData(index, intensities[1])) {
  intensities[1] = getUnfilteredGridPoint(index);
  cacheMethod.cacheData(index, intensities[1]);
}

index += sizeX-1;

if (!cacheMethod.containsCachedData(index, intensities[2])) {
  intensities[2] = getUnfilteredGridPoint(index);
  cacheMethod.cacheData(index, intensities[2]);
}

++index;

if (!cacheMethod.containsCachedData(index, intensities[3])) {
  intensities[3] = getUnfilteredGridPoint(index);
  cacheMethod.cacheData(index, intensities[3]);
}

float dx1 = intensities[0] - intensities[1];
float dx2 = intensities[2] - intensities[3];

float dy1 = intensities[0] - intensities[2];
float dy2 = intensities[1] - intensities[3];

float xFacInv = (1.0f - factors[0]);
float yFacInv = (1.0f - factors[1]);

**return Eigen::Vector3f(
  ((intensities[0] * xFacInv + intensities[1] * factors[0]) * (yFacInv)) +
  ((intensities[2] * xFacInv + intensities[3] * factors[0]) * (factors[1])),
  -((dx1 * xFacInv) + (dx2 * factors[0])),
  -((dy1 * yFacInv) + (dy2 * factors[1]))
);**

}
`

Hello sir, I'm studyding hector_mapping code with paper (A Flexible and Scalable SLAM System with Full 3D Motion Estimation).

and i wonder about gradient value of M(Pm),
the modification of paper is ∇M(Pm) = ( ∂M/∂x(Pm), ∂M/∂y(Pm) ).
but in the code, ∂M/∂y(Pm) is given first and ∂M/∂x(Pm) is given later.

∂M/∂y(Pm) = (-((dx1 * xFacInv) + (dx2 * factors[0])))
∂M/∂x(Pm) = (-((dy1 * yFacInv) + (dy2 * factors[1])))

i guess there is no problem of using hector_mapping with this code.
but i wonder this is correct code or not.

anyway, thanks for the wonderful works of you guys.
i hope i can get any info about it.

regards.

Using Mapping with VLP16-Hires - Missing TF velodyne

Dear Hector Team,
I have a question concerning your mapping package.

First of all I am using Ros Kinetic on Ubuntu 16.04.03 and
a Velodyne Lidar (VLP16 Hires).
Before I run your package I start the velodyne driver (https://github.com/ros-drivers/velodyne), so that
there is a pointcloud and a laserscan from the Lidar. It is visible
via RViz.

Then, running your package, I receive following error message:
lookupTransform base_footprint to velodyne timed out. Could not transform laser scan intobase_frame.

I looked on your code and this message is thrown because there is time out by
trying to use the tf "velodyne". It does not exist if you check it with "rosrun tf tf_monitor"
because the Velodyne Driver does not publish any tf called "velodyne".

What shall I do in order to get your code running?
Thanks,
Kevin Riehl

Segmentation Fault in Hector Slam

When I rotate my base 90 degrees, Hector Slam consistently seg faults. According to GDB, this segmentation fault occurs in GridMapCacheArray::containsCachedData(int, float&). From the source, it seems that Line 82 is the culprit: const CachedMapElement& elem (cacheArray[index]);

This is a really easy patch, but I am unsure if it points to a more serious underlying problem.

If this is because of a race condition, a simple if statement would only be covering up the problem.

Over a network /scan working but hector_mapping

I have correctly networked two ROS Kinetic laptops on LAN. One laptop,the MASTER, is for viewing and processing the info; the other laptop, the ROBOT CONTROLLER(RC), is on the robot. I'm using a RPLIDAR A2 on my robot. Its connected to the RC(Robot Controller), and is publishing over /scan topic. I'm able to view the data from /scan topic on my MASTER laptop, using Rviz. I'm then running the hector_mapping package on my MASTER, with the following mapping_default.launch file---

<?xml version="1.0"?>
<launch>
<arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
<arg name="base_frame" default="base_frame"/>
<arg name="odom_frame" default="base_frame"/>
<arg name="pub_map_odom_transform" default="true"/>
<arg name="scan_subscriber_queue_size" default="5"/>
<arg name="scan_topic" default="scan"/>
<arg name="map_size" default="2048"/>

<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">

<!-- Frame names -->
<param name="map_frame" value="map" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="odom_frame" value="$(arg odom_frame)" />

<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>

<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="map_multi_res_levels" value="2" />

<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.9" />    
<param name="map_update_distance_thresh" value="0.4"/>
<param name="map_update_angle_thresh" value="0.06" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />

<!-- Advertising config --> 
<param name="advertise_map_service" value="true"/>

<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
<param name="scan_topic" value="$(arg scan_topic)"/>
</node>    
<node pkg="tf" type="static_transform_publisher" name="map_nav_broadcaster" args="0 0 0 0 0 0 
base_frame laser 100"/>
</launch>


I'm getting the following error-----------------------------------------------------------------------------------------------

lookupTransform base_frame to laser timed out. Could not transform laser scan into base_frame


BUT THIS IS NOT IT!
When I'm running the same package on my RC(Robot Controller) Laptop with the RPLIDAR, I'm able to successfully publish over the LAN and view the map from my MASTER using Rviz.
Why isn't it working the other way around?
I've checked but I'm receiving the /scan data perfectly on my MASTER. I'm able to successfully run rplidar & hector_mapping together simultaneously on either MASTER or RC, but NOT when rplidar is on one laptop and hector_mapping on another.
I've searched the internet, wasn't able to find a solution.
Thanks in advance...

The following issue when i try to launch the SLAM

[hector_trajectory_server-3] process has died [pid 10593, exit code -6, cmd /home/ismail/catkin_ws/devel/lib/hector_trajectory_server/hector_trajectory_server __name:=hector_trajectory_server __log:=/home/ismail/.ros/log/8036bda6-c265-11e8-937a-28b2bdb04b77/hector_trajectory_server-3.log].
log file: /home/ismail/.ros/log/8036bda6-c265-11e8-937a-28b2bdb04b77/hector_trajectory_server-3*.log

Is the Hector mapping applicable for dynamic environment too?

Hi,
I am trying to use Hector mapping in dynamic environment. However, both of them are showing/mapping single obstacle twice in a map (i.e. before movement and after movement). Is there any way to get latest position (after movement) of the obstacle only?
Thanks in advance.

hector_slam package in ros melodic

Hi Can anyone help how to install hector_slam package for Melodic. I cloned hector_slam package and did catkin build, but it is failing to build. Can you suggest how to install hector_slam package for ros-melodic.
Thanks

Huge covariance values in /poseupdate

I'm getting huge covariance values from hector_mapping, both on my platform and when playing bag files with the tutorial launch files.

For instance with

$ roslaunch hector_slam_launch tutorial.launch &
$ rosbag play Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag --clock &
$ rostopic echo /poseupdate 

I get:


---
header: 
  seq: 1092
  stamp: 
    secs: 1310298019
    nsecs: 658137722
  frame_id: map
pose: 
  pose: 
    position: 
      x: 23.9624099731
      y: 17.8734512329
      z: 0.0
    orientation: 
      x: 0.0
      y: 0.0
      z: 0.299876102962
      w: 0.953978156392
  covariance: [
    96.53327941894531, -47.63311767578125, 0.0, 0.0, 0.0, -1181.0054931640625,
   -47.63311767578125, 97.9208984375, 0.0, 0.0, 0.0, 1569.2373046875,
   0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
   0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
   0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
  -1181.0054931640625, 1569.2373046875, 0.0, 0.0, 0.0, 163802.53125]

---

I'm using ROS Kinetic on Ubuntu 16.04.

no tf of map from hector_slam with only laserscan message

I want to visualization for my self-built lidarscanner in rviz. Right now display the LaserScan message in Rviz looks pretty good. Then I want to improve it with a slam demo.
First I download a scan rosbag from laser_pipeline, actually this rosbag also included odometry message. But in my case I just want to use LaserScan without odom. The launch file is use the tutorial.launch but just modified a little bit in mapping_default.launch from hector_mapping package.
mapping_default.launch:

<?xml version="1.0"?>

<launch>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Frame names -->
<param name="pub_map_odom_transform" value="true"/>
<param name="map_frame" value="map" />
<param name="base_frame" value="base_link" />
<param name="odom_frame" value="base_link" />

<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>

<!-- Map size / start point -->
<param name="map_resolution" value="0.05"/>
<param name="map_size" value="2048"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />
<param name="map_multi_res_levels" value="2" />

<param name="map_pub_period" value="2" />
<param name="laser_min_dist" value="0.4" />
<param name="laser_max_dist" value="5.5" />
<param name="output_timing" value="false" />
<param name="pub_map_scanmatch_transform" value="true" />
<!--<param name="tf_map_scanmatch_transform_frame_name" value="scanmatcher_frame" />-->

<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.7" />    
<param name="map_update_distance_thresh" value="0.2"/>
<param name="map_update_angle_thresh" value="0.06" />

<!-- Advertising config --> 
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="5"/>
<param name="scan_topic" value="base_scan"/>

</node>

    <node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 base_link base_laser_link 50"/>

</launch>

Then everything works fine. I can see the map, path, pose display well.
The tf trees:
image description
The ROSINFO:

[ INFO] [1494990764.272355175]: Waiting for tf transform data between frames /map and scanmatcher_frame to become available
HectorSM map lvl 0: cellLength: 0.05 res x:2048 res y: 2048
[ WARN] [1494990765.274379213, 85.089103132]: No transform between frames /map and scanmatcher_frame available after 85.089103 seconds of waiting. This warning only prints once.
[ INFO] [1494990765.618476795, 85.428863537]: Successfully initialized hector_geotiff MapWriter plugin TrajectoryMapWriter.
[ INFO] [1494990765.618565763, 85.441192962]: Geotiff node started
HectorSM map lvl 1: cellLength: 0.1 res x:1024 res y: 1024
[ INFO] [1494990768.046593954, 87.863962405]: HectorSM p_base_frame_: base_link
[ INFO] [1494990768.046779571, 87.863962405]: HectorSM p_map_frame_: map
[ INFO] [1494990768.047534968, 87.863962405]: HectorSM p_odom_frame_: base_link
[ INFO] [1494990768.047574313, 87.863962405]: HectorSM p_scan_topic_: base_scan
[ INFO] [1494990768.047588757, 87.863962405]: HectorSM p_use_tf_scan_transformation_: true
[ INFO] [1494990768.047600146, 87.863962405]: HectorSM p_pub_map_odom_transform_: true
[ INFO] [1494990768.047612050, 87.863962405]: HectorSM p_scan_subscriber_queue_size_: 5
[ INFO] [1494990768.047625655, 87.863962405]: HectorSM p_map_pub_period_: 2.000000
[ INFO] [1494990768.047637559, 87.863962405]: HectorSM p_update_factor_free_: 0.400000
[ INFO] [1494990768.047655522, 87.863962405]: HectorSM p_update_factor_occupied_: 0.700000
[ INFO] [1494990768.047666643, 87.863962405]: HectorSM p_map_update_distance_threshold_: 0.200000
[ INFO] [1494990768.047677684, 87.863962405]: HectorSM p_map_update_angle_threshold_: 0.060000
[ INFO] [1494990768.047689360, 87.863962405]: HectorSM p_laser_z_min_value_: -1.000000
[ INFO] [1494990768.047699443, 87.863962405]: HectorSM p_laser_z_max_value_: 1.000000
[ INFO] [1494990769.280947421, 89.100331294]: Finished waiting for tf, waited 89.100331 seconds

Then I changed the mapping_default.launch file a little to fit my llidarscanner.
The changes:

 <param name="scan_topic" value="scan"/>
 <node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 base_link laser 50"/>

Basically, just change the frame_id and LaserScan topic. After launch, In Rviz getting the error:

"No tf data. Actual error: Fixed Frame [map] does not exist."

The ROSINFO:

[ INFO] [1494991685.913714504]: Waiting for tf transform data between frames /map and scanmatcher_frame to become available
HectorSM map lvl 0: cellLength: 0.05 res x:2048 res y: 2048
[ INFO] [1494991686.044524236]: Successfully initialized hector_geotiff MapWriter plugin TrajectoryMapWriter.
[ INFO] [1494991686.044672266]: Geotiff node started
HectorSM map lvl 1: cellLength: 0.1 res x:1024 res y: 1024
[ INFO] [1494991687.097869224]: HectorSM p_base_frame_: base_link
[ INFO] [1494991687.098014701]: HectorSM p_map_frame_: map
[ INFO] [1494991687.098062504]: HectorSM p_odom_frame_: base_link
[ INFO] [1494991687.098152040]: HectorSM p_scan_topic_: scan
[ INFO] [1494991687.098197173]: HectorSM p_use_tf_scan_transformation_: true
[ INFO] [1494991687.098263787]: HectorSM p_pub_map_odom_transform_: true
[ INFO] [1494991687.098342346]: HectorSM p_scan_subscriber_queue_size_: 5
[ INFO] [1494991687.098421148]: HectorSM p_map_pub_period_: 2.000000
[ INFO] [1494991687.098485353]: HectorSM p_update_factor_free_: 0.400000
[ INFO] [1494991687.098547951]: HectorSM p_update_factor_occupied_: 0.700000
[ INFO] [1494991687.098610449]: HectorSM p_map_update_distance_threshold_: 0.200000
[ INFO] [1494991687.098674217]: HectorSM p_map_update_angle_threshold_: 0.060000
[ INFO] [1494991687.098736552]: HectorSM p_laser_z_min_value_: -1.000000
[ INFO] [1494991687.098798347]: HectorSM p_laser_z_max_value_: 1.000000

I checked and no tf existed.

Bug in interpMapValueWithDerivatives (OccGridMapUtil.h)?

It seems x and y weights are switched in derivatives at Line 341:

return Eigen::Vector3f(
((intensities[0] * xFacInv + intensities[1] * factors[0]) * (yFacInv)) +
((intensities[2] * xFacInv + intensities[3] * factors[0]) * (factors[1])),
-((dx1 * xFacInv) + (dx2 * factors[0])),
-((dy1 * yFacInv) + (dy2 * factors[1]))

should be (changes in the last two lines):

return Eigen::Vector3f(
((intensities[0] * xFacInv + intensities[1] * factors[0]) * (yFacInv)) +
((intensities[2] * xFacInv + intensities[3] * factors[0]) * (factors[1])),
-((dx1 * yFacInv) + (dx2 * factors[1])),
-((dy1 * xFacInv) + (dy2 * factors[0]))

hector_imu_attitude_to_tf flips all transforms upside down

Hi there :-)

After setting up hector_slam to run and create a map based on laser scan data contained in personal rosbags i wanted to include the use of IMU data - to account for roll and pitch motions - that is also included in the same rosbags.
For this purpose i included the hector_imu_attitude_to_tf node in my general launch file as follows:

<node pkg="hector_imu_attitude_to_tf" type="imu_attitude_to_tf_node" name="imu_attitude_to_tf_node" output="screen"> <remap from="imu_topic" to="/imu/imu"/> <param name="base_stabilized_frame" type="string" value="base_stabilized"/> <param name="base_frame" type="string" value="base_link"/> </node>

My base_frame and odom_frame are both set to "base_stabilized" since i am not using any odometry right now. The map_frame is set to "map".

When i run hector_slam with this setup all transformations of my robot model get flipped upside down (rolled by 180° about X) except the frames map and scanmatcher_frame. This is shown in figure 1.

rviz_screenshot_2017_09_13-17_31_07

In this setup my robot and laser scan data lies beneath the map plane - instead of above - and the map created by hector_slam ends up being flipped and mirrored.

For comparison figure 2 shows the same transformations without the use of hector_imu_attitude_to_tf (only a couple of the complete transforms are shown here for clearer visualisation).

rviz_screenshot_2017_09_13-17_36_26

I point out that my original IMU transformation shows a downwards pointing Z axis - as shown in figure 2. This is on purpose due to the orientation of my IMU during the data collecting process. Might this be the reason for my roll problem?

Any other thoughts on why my transformations get rolled over and turned upside down?

How could i resolve this issues?

Any help would be greatly appreciated!

Kind regards,
Koisen

Map Shifting

Hi, I'm trying to use Hector Mapping to create a map of our race track, however when approaching a second a lap the map starts shifting to the side, like in the figure below and I'm not able to create a usable map. I've tried a lot of debugging and different configurations, but nothing seems to work. Does anybody have any clue on why this happens?

map_fail

The launch files and results os rqt_graph and tf tree are shown below:
I'm using ros kinetic in ubuntu 16.04, running on a nvidia jetson tx2. The Lidar is a Hokuyo Lidar 10-LX.

transforms
default
mapping
frames
rosgraph

How does `hector_mapping` build the coordinate system?

Now I want to know the localization accuracy of hector_mapping, so I need to measure the actual position of the robot and compare it with the position of hector_mapping publish on slam_out_pose. As far as I know, after the cartographer starts, the direction in which the robot advances is defined as the positive direction of the x-axis, and then based on this coordinate system, the position information of the robot is output. Is hector_mapping based on such a mechanism to establish a coordinate system? If not, what is the `hector_mapping based on to establish the coordinate system?

my result of hector_slam is not same with your result

Hello.

I'm interested with your project. so I try to test by same bag data (Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag).

However, it is not same with your result.
I just used your source code ( catkin branch). and I refer to your tutorial (hector_slam/Tutorials/MappingUsingLoggedData, http://wiki.ros.org/hector_slam/Tutorials/MappingUsingLoggedData)

please advise me the reason why the result is not same.

Thank you in advance

Best Regards,
stmoon

result
Uploading result.png . . .

SearchDir angle change too large

When I use hector_mapping to build map, the following error occurred:

SearchDir angle change too large

My launch file is:

<launch>

  <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser" args="0 0 0.4 0 0 0 /base_footprint /laser 100" />

  <arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
  <arg name="base_frame" default="base_footprint"/>
  <arg name="odom_frame" default="odom"/>
  <arg name="pub_map_odom_transform" default="true"/>
  <arg name="scan_subscriber_queue_size" default="5"/>
  <arg name="scan_topic" default="scan"/>
  <arg name="map_size" default="2048"/>
  
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
    <!-- Frame names -->
    <param name="map_frame" value="map" />
    <param name="base_frame" value="$(arg base_frame)" />
    <param name="odom_frame" value="$(arg odom_frame)" />
    
    <!-- Tf use -->
    <param name="use_tf_scan_transformation" value="true"/>
    <param name="use_tf_pose_start_estimate" value="false"/>
    <param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.025"/>
    <param name="map_size" value="$(arg map_size)"/>
    <param name="map_start_x" value="0.5"/>
    <param name="map_start_y" value="0.5" />
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="update_factor_free" value="0.4"/>
    <param name="update_factor_occupied" value="0.9" />    
    <param name="map_update_distance_thresh" value="0.4"/>
    <param name="map_update_angle_thresh" value="0.06" />
    <param name="laser_z_min_value" value = "-1.0" />
    <param name="laser_z_max_value" value = "1.0" />
    
    <!-- Advertising config --> 
    <param name="advertise_map_service" value="true"/>    
    <param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
    <param name="scan_topic" value="$(arg scan_topic)"/>
    
    <!-- Debug parameters -->
    <!--
      <param name="output_timing" value="false"/>
      <param name="pub_drawings" value="true"/>
      <param name="pub_debug_output" value="true"/>
    -->
    <param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />
  </node>
</launch>

Unable to show bagfile in system.

A colleague and I have collected a bagfile with a LiDAR system, but we are unable to get the bagfile to play on the system. Any recommendations?

IMU candidate for hector_imu_attitude_to_tf

I am trying to use hector_imu_attitude_to_tf,

Would any one of you please recommend good IMU candidate to implement hector_imu_attitude_to_tf ?

(For example, IMU with already developed packages might be a good candidate)

Moving map around robot pose

Is it possible to move the start position of the map in realtime such that the map generated with always have its center as the robot pose? -- something like the costmap in move base. At the moment if the robot goes beyond the limits of the map size, it loses localization.

Compatibility on ROS Melodic

Hi!

I am currently operating on Ubuntu 18.04 with ROS Melodic and I wanted to use the hector_slam package (or group of package). Since there is no release for Melodic, I tried to clone the files directly in my catkin package and make a catkin_make.

But I encounter errors when compiling:
beagle@beaglebone:~/catkin_project$ catkin_make --pkg hector_mapping
Base path: /home/beagle/catkin_project
Source space: /home/beagle/catkin_project/src
Build space: /home/beagle/catkin_project/build
Devel space: /home/beagle/catkin_project/devel
Install space: /home/beagle/catkin_project/install
Creating symlink "/home/beagle/catkin_project/src/CMakeLists.txt" pointing to "/opt/ros/melodic/share/catkin/cmake/toplevel.cmake"

Running command: "cmake /home/beagle/catkin_project/src -DCATKIN_DEVEL_PREFIX=/home/beagle/catkin_project/devel -DCMAKE_INSTALL_PREFIX=/home/beagle/catkin_project/install -G Unix Makefiles" in "/home/beagle/catkin_project/build"

-- The C compiler identification is GNU 7.3.0
-- The CXX compiler identification is GNU 7.3.0
-- Check for working C compiler: /usr/bin/cc
-- Check for working C compiler: /usr/bin/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Using CATKIN_DEVEL_PREFIX: /home/beagle/catkin_project/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/melodic
-- This workspace overlays: /opt/ros/melodic
-- Found PythonInterp: /usr/bin/python2 (found suitable version "2.7.15", minimum required is "2")
-- Using PYTHON_EXECUTABLE: /usr/bin/python2
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/beagle/catkin_project/build/test_results
-- Found gmock sources under '/usr/src/googletest': gmock will be built
-- Found PythonInterp: /usr/bin/python2 (found version "2.7.15")
-- Looking for pthread.h
-- Looking for pthread.h - found
-- Looking for pthread_create
-- Looking for pthread_create - not found
-- Looking for pthread_create in pthreads
-- Looking for pthread_create in pthreads - not found
-- Looking for pthread_create in pthread
-- Looking for pthread_create in pthread - found
-- Found Threads: TRUE
-- Found gtest sources under '/usr/src/googletest': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.14
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 13 packages in topological order:
-- ~~ - hector_slam (metapackage)
-- ~~ - hector_slam_launch
-- ~~ - hector_map_tools
-- ~~ - hector_nav_msgs
-- ~~ - hector_geotiff
-- ~~ - hector_geotiff_plugins
-- ~~ - hector_marker_drawing
-- ~~ - hector_compressed_map_transport
-- ~~ - hector_imu_attitude_to_tf
-- ~~ - hector_imu_tools
-- ~~ - hector_map_server
-- ~~ - hector_trajectory_server
-- ~~ - hector_mapping
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin metapackage: 'hector_slam'
-- ==> add_subdirectory(hector_slam/hector_slam)
-- +++ processing catkin package: 'hector_slam_launch'
-- ==> add_subdirectory(hector_slam/hector_slam_launch)
-- +++ processing catkin package: 'hector_map_tools'
-- ==> add_subdirectory(hector_slam/hector_map_tools)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'hector_nav_msgs'
-- ==> add_subdirectory(hector_slam/hector_nav_msgs)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- hector_nav_msgs: 0 messages, 5 services
-- +++ processing catkin package: 'hector_geotiff'
-- ==> add_subdirectory(hector_slam/hector_geotiff)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Looking for Q_WS_X11
-- Looking for Q_WS_X11 - found
-- Looking for Q_WS_WIN
-- Looking for Q_WS_WIN - not found
-- Looking for Q_WS_QWS
-- Looking for Q_WS_QWS - not found
-- Looking for Q_WS_MAC
-- Looking for Q_WS_MAC - not found
-- Found Qt4: /usr/bin/qmake (found suitable version "4.8.7", minimum required is "4.6")
-- +++ processing catkin package: 'hector_geotiff_plugins'
-- ==> add_subdirectory(hector_slam/hector_geotiff_plugins)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'hector_marker_drawing'
-- ==> add_subdirectory(hector_slam/hector_marker_drawing)
-- +++ processing catkin package: 'hector_compressed_map_transport'
-- ==> add_subdirectory(hector_slam/hector_compressed_map_transport)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Found OpenCV: /usr (found version "3.2.0")
-- +++ processing catkin package: 'hector_imu_attitude_to_tf'
-- ==> add_subdirectory(hector_slam/hector_imu_attitude_to_tf)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'hector_imu_tools'
-- ==> add_subdirectory(hector_slam/hector_imu_tools)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'hector_map_server'
-- ==> add_subdirectory(hector_slam/hector_map_server)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'hector_trajectory_server'
-- ==> add_subdirectory(hector_slam/hector_trajectory_server)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'hector_mapping'
-- ==> add_subdirectory(hector_slam/hector_mapping)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Boost version: 1.65.1
-- Found the following Boost libraries:
-- thread
-- signals
-- chrono
-- system
-- date_time
-- atomic
-- hector_mapping: 2 messages, 0 services
-- Configuring done
-- Generating done
-- Build files have been written to: /home/beagle/catkin_project/build

Running command: "make -j1 -l1" in "/home/beagle/catkin_project/build/hector_slam/hector_mapping"

Scanning dependencies of target _hector_mapping_generate_messages_check_deps_HectorDebugInfo
[ 0%] Built target _hector_mapping_generate_messages_check_deps_HectorDebugInfo
Scanning dependencies of target _hector_mapping_generate_messages_check_deps_HectorIterData
[ 0%] Built target _hector_mapping_generate_messages_check_deps_HectorIterData
Scanning dependencies of target hector_mapping_generate_messages_py
[ 6%] Generating Python from MSG hector_mapping/HectorIterData
[ 12%] Generating Python from MSG hector_mapping/HectorDebugInfo
[ 18%] Generating Python msg init.py for hector_mapping
[ 18%] Built target hector_mapping_generate_messages_py
Scanning dependencies of target hector_mapping_generate_messages_eus
[ 25%] Generating EusLisp code from hector_mapping/HectorIterData.msg
[ 31%] Generating EusLisp code from hector_mapping/HectorDebugInfo.msg
[ 37%] Generating EusLisp manifest code for hector_mapping
[ 37%] Built target hector_mapping_generate_messages_eus
Scanning dependencies of target hector_mapping_generate_messages_cpp
[ 43%] Generating C++ code from hector_mapping/HectorIterData.msg
[ 50%] Generating C++ code from hector_mapping/HectorDebugInfo.msg
[ 50%] Built target hector_mapping_generate_messages_cpp
Scanning dependencies of target hector_mapping_generate_messages_lisp
[ 56%] Generating Lisp code from hector_mapping/HectorIterData.msg
[ 62%] Generating Lisp code from hector_mapping/HectorDebugInfo.msg
[ 62%] Built target hector_mapping_generate_messages_lisp
Scanning dependencies of target hector_mapping_generate_messages_nodejs
[ 68%] Generating Javascript code from hector_mapping/HectorIterData.msg
[ 75%] Generating Javascript code from hector_mapping/HectorDebugInfo.msg
[ 75%] Built target hector_mapping_generate_messages_nodejs
Scanning dependencies of target hector_mapping_generate_messages
[ 75%] Built target hector_mapping_generate_messages
Scanning dependencies of target hector_mapping
[ 81%] Building CXX object hector_slam/hector_mapping/CMakeFiles/hector_mapping.dir/src/HectorMappingRos.cpp.o
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-7/README.Bugs for instructions.
hector_slam/hector_mapping/CMakeFiles/hector_mapping.dir/build.make:62: recipe for target 'hector_slam/hector_mapping/CMakeFiles/hector_mapping.dir/src/HectorMappingRos.cpp.o' failed
make[2]: *** [hector_slam/hector_mapping/CMakeFiles/hector_mapping.dir/src/HectorMappingRos.cpp.o] Error 4
CMakeFiles/Makefile2:3997: recipe for target 'hector_slam/hector_mapping/CMakeFiles/hector_mapping.dir/all' failed
make[1]: *** [hector_slam/hector_mapping/CMakeFiles/hector_mapping.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j1 -l1" failed

If anyone has a clue of how I could use hector_slam on ROS Melodic, I will be very grateful!

Default catkin build ~20x slower than building Release mode

As noted by others on ROS Answers, hector_mapping recently started consuming much more CPU than before. I did some testing using the "catkin" branch today. Compiling as normal using catkin_make, scanmatching times look like this (first number is total callback time including waiting for tf, second one is pure scanmatching time):

[ INFO] [1398499404.260625679, 1310298079.788137032]: HectorSLAM Iter took: 21.483526 milliseconds 20.659422
[ INFO] [1398499404.296399162, 1310298079.828412026]: HectorSLAM Iter took: 35.544626 milliseconds 19.764313
[ INFO] [1398499404.317099143, 1310298079.848542918]: HectorSLAM Iter took: 20.477672 milliseconds 19.699650
[ INFO] [1398499404.336751351, 1310298079.868703373]: HectorSLAM Iter took: 19.414648 milliseconds 18.561415
[ INFO] [1398499404.356968387, 1310298079.888838836]: HectorSLAM Iter took: 20.045855 milliseconds 19.270421
[ INFO] [1398499404.377869501, 1310298079.908976178]: HectorSLAM Iter took: 20.676452 milliseconds 19.893793
[ INFO] [1398499404.428192094, 1310298079.959350752]: HectorSLAM Iter took: 50.146126 milliseconds 20.291206
[ INFO] [1398499404.449260025, 1310298079.979689020]: HectorSLAM Iter took: 20.856226 milliseconds 19.955497
[ INFO] [1398499404.469981423, 1310298079.999769104]: HectorSLAM Iter took: 20.585382 milliseconds 19.826378
[ INFO] [1398499404.490544122, 1310298080.019994667]: HectorSLAM Iter took: 20.372438 milliseconds 19.613348
[ INFO] [1398499404.511467850, 1310298080.040130785]: HectorSLAM Iter took: 20.798515 milliseconds 20.017045

As can be seen, scanmatching routinely takes ~20ms. I tried compiling hector_mapping with specific setting of Release mode (which I thought shouldn´t make a difference):

catkin_make --pkg hector_mapping -DCMAKE_BUILD_TYPE=Release

The runtimes then look like this:

[ INFO] [1398499504.912731262, 1310298008.069057577]: HectorSLAM Iter took: 3.711615 milliseconds 2.990415
[ INFO] [1398499504.945980306, 1310298008.099356322]: HectorSLAM Iter took: 0.620438 milliseconds 0.416393
[ INFO] [1398499504.987072007, 1310298008.139718203]: HectorSLAM Iter took: 1.600975 milliseconds 0.936554
[ INFO] [1398499504.989084507, 1310298008.139718203]: HectorSLAM Iter took: 1.572179 milliseconds 0.872445
[ INFO] [1398499505.026960059, 1310298008.180107810]: HectorSLAM Iter took: 1.506644 milliseconds 0.854052
[ INFO] [1398499505.028632274, 1310298008.180107810]: HectorSLAM Iter took: 1.432552 milliseconds 0.837005
[ INFO] [1398499505.065857676, 1310298008.220403686]: HectorSLAM Iter took: 0.541332 milliseconds 0.338279
[ INFO] [1398499505.078232589, 1310298008.230520841]: HectorSLAM Iter took: 1.826754 milliseconds 1.048584
[ INFO] [1398499505.115244963, 1310298008.270901025]: HectorSLAM Iter took: 1.697194 milliseconds 1.008361
[ INFO] [1398499505.165472520, 1310298008.321368063]: HectorSLAM Iter took: 12.020634 milliseconds 0.911040

This is about 20x faster than when not building Release explicitly and in the performance ballpark that is expected (and that was the norm using rosbuild).

It thus looks like the compile options used (or the use of catkin within hector_slam) is somehow wrong.

Maybe there's a bug in tf tree

I found a bug when played bag file "Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag":

  1. Rosbag play it
  2. Uncheck Pose in rviz
  3. Add TF and view it in rviz
  4. You will find that the base_footprint,base_link,base_stabilized and laser frames are jumping between map frame and scanmatcher_frame frame.

Those frames near the scanmatcher_frame is correct, it just like at time0 slam core broadcast the correct tf like scanmatcher_frame->(compute)->base_link, then it was replaced by another static broadcaster to odom->(fixed)->base_link at time1, then cycling.

This source code is too difficult to read, so I don't know where the problem is., and I'm looking forward to your reply, thanks.

Sincerely

is there anything to analyze hector slam?

Hi..

I have analyzed hector slam. however it is difficult for me to analyze.'
Is there any papers or technical note for analysis?

I just got one paper (a flexible and scalable SLAM system with full 3d motion estimation)

Thank you in advance

Release for jade

hector_slam is currently available for indigo. Will it be also included in jade release? It builds just fine from source on jade, but it would be nice to have it in repo.

Low Frequency of Estimated Pose on Ubuntu 18.04

Hi

I've been using hector_mapping on Odroid XU4 and Ubuntu 14.04(Lubuntu) without any problem and getting ~40Hz of estimated pose on /poseupdate and /slam_out_pose topics.

I switched to Ubuntu 18.04(Mate) and after compiling and using the same launch file I'm now getting around ~7 Hz of Pose in those topics

does anyone know how to fix this issue ?

here's my launch file

<?xml version="1.0"?>

<launch>
	<master auto="yes"/>
<include file="/home/odroid/ROSLaunchfiles/hector2D/2dmap_dev.launch"><!--LaserScanner Node starter-->
</include>
  <arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
  <arg name="base_frame" default="/laser0_frame"/> 
  <arg name="odom_frame" default="/laser0_frame"/> 
  <arg name="pub_map_odom_transform" default="true"/>
  <arg name="scan_subscriber_queue_size" default="10"/>
  <arg name="scan_topic" default="scan"/>
  <arg name="map_size" default="1024"/>
  
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">   
    <!-- Frame names -->
    <param name="map_frame" value="/base_link" />
    <param name="base_frame" value="$(arg base_frame)" />
    <param name="odom_frame" value="$(arg odom_frame)" />
    
    <!-- Tf use -->
    <param name="use_tf_scan_transformation" value="true"/>
    <param name="use_tf_pose_start_estimate" value="false"/>
    <param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
    
    <!-- Map size / start point -->
    <param name="map_resolution" value="0.050"/>
    <param name="map_size" value="$(arg map_size)"/>
    <param name="map_start_x" value="0.5"/>
    <param name="map_start_y" value="0.5" />
    <param name="map_multi_res_levels" value="2" />
    
    <!-- Map update parameters -->
    <param name="update_factor_free" value="0.4"/>
    <param name="update_factor_occupied" value="0.9" />    
    <param name="map_update_distance_thresh" value="0.1"/>
    <param name="map_update_angle_thresh" value="0.04" />
    <param name="laser_z_min_value" value = "-1.0" />
    <param name="laser_z_max_value" value = "1.0" />
    
    <!-- Advertising config --> 
    <param name="advertise_map_service" value="true"/>
    <param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
    <param name="scan_topic" value="$(arg scan_topic)"/>
    <param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />
  </node>
 
  <arg name="trajectory_source_frame_name" default="/scanmatcher_frame"/>
  <arg name="trajectory_update_rate" default="4"/>
  <arg name="trajectory_publish_rate" default="0.25"/>
  <arg name="map_file_path" default="$(find hector_geotiff)/maps"/>
  <arg name="map_file_base_name" default="hector_slam_map"/>

  <node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen">
    <param name="target_frame_name" type="string" value="/map" />
    <param name="source_frame_name" type="string" value="$(arg trajectory_source_frame_name)" />
    <param name="trajectory_update_rate" type="double" value="$(arg trajectory_update_rate)" />
    <param name="trajectory_publish_rate" type="double" value="$(arg trajectory_publish_rate)" />
  </node>

  <node pkg="hector_geotiff" type="geotiff_node" name="hector_geotiff_node" output="screen" launch-prefix="nice -n 15">
    <remap from="map" to="/dynamic_map" />
    <param name="map_file_path" type="string" value="$(arg map_file_path)" />
    <param name="map_file_base_name" type="string" value="$(arg map_file_base_name)" />
    <param name="geotiff_save_period" type="double" value="0" />
    <param name="draw_background_checkerboard" type="bool" value="true" />
    <param name="draw_free_space_grid" type="bool" value="true" />
    <param name="plugins" type="string" value="hector_geotiff_plugins/TrajectoryMapWriter" />
  </node>

</launch>

rviz_cfg not present

roslaunch hector_slam_launch tutorial.launch points to an rviz_cfg folder in the hector_slam_launch folder, but no such folder or mapping_demo.rviz file exists after install of hector_slam.

It looks like the rviz configs are present in the source version of hector_slam_launch, but aren't installed properly.

How to load a map in the hector_slam for the resumption of the hector_slam in uncharted areas

On the first day, using hector_slam, I create a corridor map and save it via map_saver.
On the second day, I need to load the map into the hector_slam and continue creating the map in the unexplored rooms.
If I upload a map to hector_slam using map_saver, it will simply be erased.
How to save a map from hector_slam so that it can be loaded back into it and continue research in unknown areas?

is there a bug in OccGridMapUtil.h

Recently , I'm trying to analyze you hector slam code, and I also read the paper that you have published.
I find the function "Eigen::Vector3f interpMapValueWithDerivatives(const Eigen::Vector2f& coords)" in OccGridMapUtil.h return a vector is somewhat inconsistent with the paper.

    return Eigen::Vector3f(
      ((intensities[0] * xFacInv + intensities[1] * factors[0]) * (yFacInv)) +
      ((intensities[2] * xFacInv + intensities[3] * factors[0]) * (factors[1])),
      -((dx1 * xFacInv) + (dx2 * factors[0])),
      -((dy1 * yFacInv) + (dy2 * factors[1]))
    );

should be

    return Eigen::Vector3f(
      ((intensities[0] * xFacInv + intensities[1] * factors[0]) * (yFacInv)) +
      ((intensities[2] * xFacInv + intensities[3] * factors[0]) * (factors[1])),
      -((dx1 * yFacInv) + (dx2 * factors[1])),
      -((dy1 * xFacInv) + (dy2 * factors[0]))
    );

is there a bug ?

∂M /∂x (Pm) ≈ (( y − y0 )/(y1 − y0))(M(P11)-M(P01)) + (( y1 − y )/(y1 − y0))(M(P10)-M(P00))
∂M /∂y (Pm) ≈ ((x − x0)/(x1 − x0))(M(P11)-M(P10)) + ((x1− x)/(x1 − x0))(M(P01)-M(P00))

Hector mapping with RealSense R200

Hi everyone!

I am currently trying to generate a 2d map using the RealSense R200 camera from Intel. However, I have some problem building the 2d map. I am using the depth image to laser scan package from ROS to convert the depth image into a fake laser scan for the input to the hector mapping. Below is my current tf transform in the hector mapping.
<node pkg="tf" type="static_transform_publisher" name="map_2_base_footprint" args="0 0 0 0 0 0 /map /base_footprint 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_footprint_2_base_link" args="0 0 0 0 0 0 /base_footprint /base_link 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_to_base_stablized" args="0 0 0 0 0 0 /base_link /base_stablized 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_to_realsense" args="0 0 0.6 -1.5707963 0 -1.5707963 /base_link /realsense_frame 100" />
<node pkg="tf" type="static_transform_publisher" name="base_stablized_2_base_frame" args="0 0 0 0 0 0 /base_stablized /base_frame 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_frame_2_laser_link" args="0 0 0 0 0 0 /base_frame /camera_link 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_2_nav_link" args="0 0 0 0 0 0 /base_frame /nav 100"/>

Does the problem lie with the tf transform?

Any way to easily "Pause" hector slam or temporarily ignore scans

Thanks for this code, it works well for me with a Sick Laser. I am wondering if you have any advice on the best way to temporarily suspend localization (or if I am doing something wrong). I want to sweep the laser to build the 3d view but when I do it hector_slam interprets it as a movement of the base_link. I expected that since the tf between scan_frame and base_frame was changing hector_slam would know it wasn't a true base_link movement. So I thought possibly I could just stop doing slam during a sweep of the laser since the robot is stationary during that time anyway.

trouble with groovy and Fuerte

Hi guys
I try to Run example in README but when Launch the "hector_slam_launch tutorial.launch"
This error occured
"ERROR: the config file '/opt/ros/groovy/stacks/hector_slam/hector_slam_launch/rviz_cfg/mapping_demo.vcg' is a .vcg file, which is the old rviz config format.
New config files have a .rviz extension and use YAML formatting. The format changed
between Fuerte and Groovy. There is not (yet) an automated conversion program."
How can I fix this?
for run the example do I need the Fuerte or this example run in groovy?

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.