Giter Club home page Giter Club logo

slam_toolbox's Introduction

Slam Toolbox

We've received feedback from users and have robots operating in the following environments with SLAM Toolbox:

  • Retail
  • Warehouses
  • Libraries
  • Research

It is also the currently supported ROS2-SLAM library. See tutorials for working with it in ROS2 Navigation here.

Cite This Work

You can find this work here and clicking on the image below.

Macenski, S., Jambrecic I., "SLAM Toolbox: SLAM for the dynamic world", Journal of Open Source Software, 6(61), 2783, 2021.

Macenski, S., "On Use of SLAM Toolbox, A fresh(er) look at mapping and localization for the dynamic world", ROSCon 2019.

IMAGE ALT TEXT

Introduction

Slam Toolbox is a set of tools and capabilities for 2D SLAM built by Steve Macenski while at Simbe Robotics, maintained while at Samsung Research, and largely in his free time.

This project contains the ability to do most everything any other available SLAM library, both free and paid, and more. This includes:

  • Ordinary point-and-shoot 2D SLAM mobile robotics folks expect (start, map, save pgm file) with some nice built in utilities like saving maps
  • Continuing to refine, remap, or continue mapping a saved (serialized) pose-graph at any time
  • life-long mapping: load a saved pose-graph continue mapping in a space while also removing extraneous information from newly added scans
  • an optimization-based localization mode built on the pose-graph. Optionally run localization mode without a prior map for "lidar odometry" mode with local loop closures
  • synchronous and asynchronous modes of mapping
  • kinematic map merging (with an elastic graph manipulation merging technique in the works)
  • plugin-based optimization solvers with a new optimized Google Ceres based plugin
  • RVIZ plugin for interacting with the tools
  • graph manipulation tools in RVIZ to manipulate nodes and connections during mapping
  • Map serialization and lossless data storage
  • ... more but those are the highlights

For running on live production robots, I recommend using the snap: slam-toolbox, it has optimizations in it that make it about 10x faster. You need the deb/source install for the other developer level tools that don't need to be on the robot (rviz plugins, etc).

This package has been benchmarked mapping building at 5x+ real-time up to about 30,000 sq. ft. and 3x real-time up to about 60,000 sq. ft. with the largest area (I'm aware of) used was a 200,000 sq. ft. building in synchronous mode (i.e. processing all scans, regardless of lag), and much larger spaces in asynchronous mode.

The video below was collected at Circuit Launch in Oakland, California. Thanks to Silicon Valley Robotics & Circuit Launch for being a testbed for some of this work.

map_image

An overview of how the map was generated is presented below: slam_toolbox_sync_diagram

  1. ROS Node: SLAM toolbox is run in synchronous mode, which generates a ROS node. This node subscribes to laser scan and odometry topics, and publishes map to odom transform and a map.
  2. Get odometry and LIDAR data: A callback for the laser topic will generate a pose (using odometry) and a laser scan tied at that node. These PosedScan objects form a queue, which are processed by the algorithm.
  3. Process Data: The queue of PosedScan objects are used to construct a pose graph; odometry is refined using laser scan matching. This pose graph is used to compute robot pose, and find loop closures. If a loop closure is found, the pose graph is optimized, and pose estimates are updated. Pose estimates are used to compute and publish a map to odom transform for the robot.
  4. Mapping: Laser scans associated with each pose in the pose graph are used to construct and publish a map.

Support and Contribution

If you have any questions on use or configuration, please post your questions on ROS Answers and someone from the community will work their hardest to get back to you. Tangible issues in the codebase or feature requests should be made with GitHub issues.

If you're interested in contributing to this project in a substantial way, please file a public GitHub issue on your new feature / patch. If for some reason the development of this feature is sensitive, please email the maintainers at their email addresses listed in the package.xml file.

For all contributions, please properly fill in the GitHub issue and PR templates with all necessary context. All PRs must be passing CI and maintaining ABI compatibility within released ROS distributions. A maintainer will follow up shortly thereafter.

03/23/2021 Note On Serialized Files

As of 03/23/2021, the contents of the serialized files has changed. For all new users after this date, this regard this section it does not impact you.

If you have previously existing serialized files (e.g. not pgm maps, but .posegraph serialized slam sessions), after this date, you may need to take some action to maintain current features. Unfortunately, an ABI breaking change was required to be made in order to fix a very large bug affecting any 360 or non-axially-mounted LIDAR system.

This Discourse post highlights the issues. The frame storing the scan data for the optimizer was incorrect leading to explosions or flipping of maps for 360 and non-axially-aligned robots when using conservative loss functions. This change permanently fixes this issue, however it changes the frame of reference that this data is stored and serialized in. If your system as a non-360 lidar and it is mounted with its frame aligned with the robot base frame, you're unlikely to notice a problem and can disregard this statement. For all others noticing issues, you have the following options:

  • Use the <distro>-devel-unfixed branch rather than <distro>-devel, which contains the unfixed version of this distribution's release which will be maintained in parallel to the main branches to have an option to continue with your working solution
  • Convert your serialized files into the new reference frame with an offline utility
  • Take the raw data and rerun the SLAM sessions to get a new serialized file with the right content

More of the conversation can be seen on tickets #198 and #281. I apologize for the inconvenience, however this solves a very large bug that was impacting a large number of users. I've worked hard to make sure there's a viable path forward for everyone.

LifeLong Mapping

LifeLong mapping is the concept of being able to map a space, completely or partially, and over time, refine and update that map as you continue to interact with the space. Our approach implements this and also takes care to allow for the application of operating in the cloud, as well as mapping with many robots in a shared space (cloud distributed mapping). While Slam Toolbox can also just be used for a point-and-shoot mapping of a space and saving that map as a .pgm file as maps are traditionally stored in, it also allows you to save the pose-graph and metadata losslessly to reload later with the same or different robot and continue to map the space.

Our lifelong mapping consists of a few key steps

  • Serialization and Deserialization to store and reload map information
  • KD-Tree search matching to locate the robot in its position on reinitialization
  • pose-graph optimization based SLAM with 2D scan matching abstraction

This will allow the user to create and update existing maps, then serialize the data for use in other mapping sessions, something sorely lacking from most SLAM implementations and nearly all planar SLAM implementations. Other good libraries that do this include RTab-Map and Cartographer, though they themselves have their own quirks that make them (in my opinion) unusable for production robotics applications. This library provides the mechanics to save not only the data, but the pose graph, and associated metadata to work with. This has been used to create maps by merging techniques (taking 2 or more serialized objects and creating 1 globally consistent one) as well as continuous mapping techniques (updating 1, same, serialized map object over time and refining it). The major benefit of this over RTab-Map or Cartographer is the maturity of the underlying (but heavily modified) open_karto library the project is based on. The scan matcher of Karto is well known as an extremely good matcher for 2D laser scans and modified versions of Karto can be found in companies across the world.

Slam Toolbox supports all the major modes:

  • Starting from a predefined dock (assuming to be near start region)
  • Starting at any particular node - select a node ID to start near
  • Starting in any particular area - indicate current pose in the map frame to start at, like AMCL

In the RVIZ interface (see section below) you'll be able to re-localize in a map or continue mapping graphically or programmatically using ROS services.

On time of writing: there a highly experimental implementation of what I call "true lifelong" mapping that does support the method for removing nodes over time as well as adding nodes, this results in a true ability to map for life since the computation is bounded by removing extraneous or outdated information. Its recommended to run the non-full LifeLong mapping mode in the cloud for the increased computational burdens if you'd like to be continuously refining a map. However a real and desperately needed application of this is to have multi-session mapping to update just a section of the map or map half an area at a time to create a full (and then static) map for AMCL or Slam Toolbox localization mode, which this will handle in spades. The immediate plan is to create a mode within LifeLong mapping to decay old nodes to bound the computation and allow it to run on the edge by refining the experimental node. Continuing mapping (lifelong) should be used to build a complete map then switch to the pose-graph deformation localization mode until node decay is implemented, and you should not see any substantial performance impacts.

Localization

Localization mode consists of 3 things:

  • Loads existing serialized map into the node
  • Maintains a rolling buffer of recent scans in the pose-graph
  • After expiring from the buffer scans are removed and the underlying map is not affected

Localization methods on image map files has been around for years and works relatively well. There has not been a great deal of work in academia to refine these algorithms to a degree that satisfies me. However SLAM is a rich and well benchmarked topic. The inspiration of this work was the concept of "Can we make localization, SLAM again?" such that we can take advantage of all the nice things about SLAM for localization, but remove the unbounded computational increase.

To enable, set mode: localization in the configuration file to allow for the Ceres plugin to set itself correctly to be able to quickly add and remove nodes and constraints from the pose graph, but isn't strictly required, but a performance optimization. The localization mode will automatically load your pose graph, take the first scan and match it against the local area to further refine your estimated position, and start localizing.

To minimize the amount of changes required for moving to this mode over AMCL, we also expose a subscriber to the /initialpose topic used by AMCL to relocalize to a position, which also hooks up to the 2D Pose Estimation tool in RVIZ. This way you can enter localization mode with our approach but continue to use the same API as you expect from AMCL for ease of integration.

In summary, this approach I dub elastic pose-graph localization is where we take existing map pose-graphs and localized with-in them with a rolling window of recent scans. This way we can localize in an existing map using the scan matcher, but not update the underlaying map long-term should something go wrong. It can be considered a replacement to AMCL and results is not needing any .pgm maps ever again. The lifelong mapping/continuous slam mode above will do better if you'd like to modify the underlying graph while moving. This method of localization might not be suitable for all applications, it does require quite a bit of tuning for your particular robot and needs high quality odometry. If in doubt, you're always welcome to use other 2D map localizers in the ecosystem like AMCL. For most beginners or users looking for a good out of the box experience, I'd recommend AMCL.

Tools

Plugin based Optimizers

I have created a pluginlib interface for the ScanSolver abstract class so that you can change optimizers on runtime to test many different ones if you like.

Then I generated plugins for a few different solvers that people might be interested in. I like to swap them out for benchmarking and make sure its the same code running for all. I have supported Ceres, G2O, SPA, and GTSAM.

GTSAM/G2O/SPA is currently "unsupported" although all the code is there. They don't outperform Ceres settings I describe below so I stopped compiling them to save on build time, but they're there and work if you would like to use them. PRs to implement other optimizer plugins are welcome.

Map Merging - Example uses of serialized raw data & posegraphs

Kinematic

This uses RVIZ and the plugin to load any number of posegraphs that will show up in RVIZ under map_N and a set of interactive markers to allow you to move them around. Once you have them all positioned relative to each other in the way you like, you can merge the submaps into a global map which can be downloaded with your map server implementation of choice.

It's more of a demonstration of other things you can do once you have the raw data to work with, but I don't suspect many people will get much use out of it unless you're used to stitching maps by hand.

More information in the RVIZ Plugin section below.

RVIZ Plugin

An rviz plugin is furnished to help with manual loop closures and online / offline mapping. By default interactive mode is off (allowing you to move nodes) as this takes quite a toll on rviz. When you want to move nodes, tick the interactive box, move what you want, and save changes to prompt a manual loop closure. Clear if you made a mistake. When done, exit interactive mode again.

There's also a tool to help you control online and offline data. You can at any time stop processing new scans or accepting new scans into the queue. This is desirable when you want to allow the package to catch up while the robot sits still (This option is only meaningful in synchronous mode. In asynchronous mode the robot will never fall behind.) or you want to stop processing new scans while you do a manual loop closure / manual "help". If there's more in the queue than you want, you may also clear it.

Additionally there's exposed buttons for the serialization and deserialization services to load an old pose-graph to update and refine, or continue mapping, then save back to file. The "Start By Dock" checkbox will try to scan match against the first node (assuming you started at your dock) to give you an odometry estimate to start with. Another option is to start using an inputted position in the GUI or by calling the underlying service. Additionally, you can use the current odometric position estimation if you happened to have just paused the robot or not moved much between runs. Finally (and most usefully), you can use the RVIZ tool for 2D Pose Estimation to tell it where to go in localization mode just like AMCL.

Additionally the RVIZ plugin will allow you to add serialized map files as submaps in RVIZ. They will be displayed with an interactive marker you can translate and rotate to match up, then generate a composite map with the Generate Map button. At that point the composite map is being broadcasted on the /map topic and you can save it with the map_saver.

It's recommended to always continue mapping near the dock, if that's not possible, look into the starting from pose or map merging techniques. This RVIZ plugin is mostly here as a debug utility, but if you often find yourself mapping areas using rviz already, I'd just have it open. All the RVIZ buttons are implemented using services that a master application can control.

The interface is shown below.

rviz_plugin

Graph Manipulation

By enabling Interactive Mode, the graph nodes will change from markers to interactive markers which you can manipulate. When you move a node(s), you can Save Changes and it will send the updated position to the pose-graph and cause an optimization run to occur to change the pose-graph with your new node location. This is helpful if the robot gets pushed, slips, runs into a wall, or otherwise has drifting odometry and you would like to manually correct it.

When a map is sufficiently large, the number of interactive markers in RVIZ may be too large and RVIZ may start to lag. I only recommend using this feature as a testing debug tool and not for production. However if you are able to make it work with 10,000 interactive markers, I'll merge that PR in a heartbeat. Otherwise I'd restrict the use of this feature to small maps or with limited time to make a quick change and return to static mode by unchecking the box.

Metrics

If you're a weirdo like me and you want to see how I came up with the settings I had for the Ceres optimizer, see below.

ceres_solver_comparison

The data sets present solve time vs number of nodes in the pose graph on a large dataset, as that is not open source, but suffice to say that the settings I recommend work well. I think anyone would be hard set in a normal application to exceed or find that another solver type is better (that super low curve on the bottom one, yeah, that's it). Benchmark on a low power 7th gen i7 machine.

It can map very large spaces with reasonable CPU and memory consumption. My default settings increase O(N) on number of elements in the pose graph. I recommend from extensive testing to use the SPARSE_NORMAL_CHOLESKY solver with Ceres and the SCHUR_JACOBI preconditioner. Using LM at the trust region strategy is comparable to the dogleg subspace strategy, but LM is much better supported so why argue with it.

You can get away without a loss function if your odometry is good (i.e. likelihood for outliers is extremely low). If you have an abnormal application or expect wheel slippage, I might recommend a HuberLoss function, which is a really good catch-all loss function if you're looking for a place to start. All these options and more are available from the ROS parameter server.

API

The following are the services/topics that are exposed for use. See the rviz plugin for an implementation of their use.

Subscribed topics

/scan sensor_msgs/LaserScan the input scan from your laser to utilize
tf N/A a valid transform from your configured odom_frame to base_frame

Published topics

Topic Type Description
map nav_msgs/OccupancyGrid occupancy grid representation of the pose-graph at map_update_interval frequency
pose geometry_msgs/PoseWithCovarianceStamped pose of the base_frame in the configured map_frame along with the covariance calculated from the scan match

Exposed Services

Topic Type Description
/slam_toolbox/clear_changes slam_toolbox/Clear Clear all manual pose-graph manipulation changes pending
/slam_toolbox/deserialize_map slam_toolbox/DeserializePoseGraph Load a saved serialized pose-graph files from disk
/slam_toolbox/dynamic_map nav_msgs/OccupancyGrid Request the current state of the pose-graph as an occupancy grid
/slam_toolbox/manual_loop_closure slam_toolbox/LoopClosure Request the manual changes to the pose-graph pending to be processed
/slam_toolbox/pause_new_measurements slam_toolbox/Pause Pause processing of new incoming laser scans by the toolbox
/slam_toolbox/save_map slam_toolbox/SaveMap Save the map image file of the pose-graph that is useable for display or AMCL localization. It is a simple wrapper on map_server/map_saver but is useful.
/slam_toolbox/serialize_map slam_toolbox/SerializePoseGraph Save the map pose-graph and datathat is useable for continued mapping, slam_toolbox localization, offline manipulation, and more
/slam_toolbox/toggle_interactive_mode slam_toolbox/ToggleInteractive Toggling in and out of interactive mode, publishing interactive markers of the nodes and their positions to be updated in an application
/slam_toolbox/reset slam_toolbox/Reset Reset current map back to the initial state

Configuration

The following settings and options are exposed to you. My default configuration is given in config directory.

Solver Params

solver_plugin - The type of nonlinear solver to utilize for karto's scan solver. Options: solver_plugins::CeresSolver, solver_plugins::SpaSolver, solver_plugins::G2oSolver. Default: solver_plugins::CeresSolver.

ceres_linear_solver - The linear solver for Ceres to use. Options: SPARSE_NORMAL_CHOLESKY, SPARSE_SCHUR, ITERATIVE_SCHUR, CGNR. Defaults to SPARSE_NORMAL_CHOLESKY.

ceres_preconditioner - The preconditioner to use with that solver. Options: JACOBI, IDENTITY (none), SCHUR_JACOBI. Defaults to JACOBI.

ceres_trust_strategy - The trust region strategy. Line search strategies are not exposed because they perform poorly for this use. Options: LEVENBERG_MARQUARDT, DOGLEG. Default: LEVENBERG_MARQUARDT.

ceres_dogleg_type - The dogleg strategy to use if the trust strategy is DOGLEG. Options: TRADITIONAL_DOGLEG, SUBSPACE_DOGLEG. Default: TRADITIONAL_DOGLEG

ceres_loss_function - The type of loss function to reject outlier measurements. None is equatable to a squared loss. Options: None, HuberLoss, CauchyLoss. Default: None.

mode - "mapping" or "localization" mode for performance optimizations in the Ceres problem creation

Toolbox Params

odom_frame - Odometry frame

map_frame - Map frame

base_frame - Base frame

scan_topic - scan topic, absolute path, i.e. /scan not scan

scan_queue_size - The number of scan messages to queue up before throwing away old ones. Should always be set to 1 in async mode

use_map_saver - Instantiate the map saver service and self-subscribe to the map topic

map_file_name - Name of the pose-graph file to load on startup if available

map_start_pose - Pose to start pose-graph mapping/localization in, if available

map_start_at_dock - Starting pose-graph loading at the dock (first node), if available. If both pose and dock are set, it will use pose

debug_logging - Change logger to debug

throttle_scans - Number of scans to throttle in synchronous mode

transform_publish_period - The map to odom transform publish period. 0 will not publish transforms

map_update_interval - Interval to update the 2D occupancy map for other applications / visualization

enable_interactive_mode - Whether or not to allow for interactive mode to be enabled. Interactive mode will retain a cache of laser scans mapped to their ID for visualization in interactive mode. As a result the memory for the process will increase. This is manually disabled in localization and lifelong modes since they would increase the memory utilization over time. Valid for either mapping or continued mapping modes.

position_covariance_scale - Amount to scale position covariance when publishing pose from scan match. This can be used to tune the influence of the pose position in a downstream localization filter. The covariance represents the uncertainty of the measurement, so scaling up the covariance will result in the pose position having less influence on downstream filters. Default: 1.0

yaw_covariance_scale - Amount to scale yaw covariance when publishing pose from scan match. See description of position_covariance_scale. Default: 1.0

resolution - Resolution of the 2D occupancy map to generate

max_laser_range - Maximum laser range to use for 2D occupancy map rasterizing

minimum_time_interval - The minimum duration of time between scans to be processed in synchronous mode

transform_timeout - TF timeout for looking up transforms

tf_buffer_duration - Duration to store TF messages for lookup. Set high if running offline at multiple times speed in synchronous mode.

stack_size_to_use - The number of bytes to reset the stack size to, to enable serialization/deserialization of files. A liberal default is 40000000, but less is fine.

minimum_travel_distance - Minimum distance of travel before processing a new scan

localization_on_configure - Set to true to set the localization mode to localization during node on_configure transition. Set to false to set the localization mode to mapping instead. Only applies to map_and_localization_slam_toolbox node.

Matcher Params

use_scan_matching - whether to use scan matching to refine odometric pose (uh, why would you not?)

use_scan_barycenter - Whether to use the barycenter or scan pose

minimum_travel_heading - Minimum changing in heading to justify an update

scan_buffer_size - The number of scans to buffer into a chain, also used as the number of scans in the circular buffer of localization mode

scan_buffer_maximum_scan_distance - Maximum distance of a scan from the pose before removing the scan from the buffer

link_match_minimum_response_fine - The threshold link matching algorithm response for fine resolution to pass

link_scan_maximum_distance - Maximum distance between linked scans to be valid

loop_search_maximum_distance - Maximum threshold of distance for scans to be considered for loop closure

do_loop_closing - Whether to do loop closure (if you're not sure, the answer is "true")

loop_match_minimum_chain_size - The minimum chain length of scans to look for loop closure

loop_match_maximum_variance_coarse - The threshold variance in coarse search to pass to refine

loop_match_minimum_response_coarse - The threshold response of the loop closure algorithm in coarse search to pass to refine

loop_match_minimum_response_fine - The threshold response of the loop closure algorithm in fine search to pass to refine

correlation_search_space_dimension - Search grid size to do scan correlation over

correlation_search_space_resolution - Search grid resolution to do scan correlation over

correlation_search_space_smear_deviation - Amount of multimodal smearing to smooth out responses

loop_search_space_dimension - Size of the search grid over the loop closure algorithm

loop_search_space_resolution - Search grid resolution to do loop closure over

loop_search_space_smear_deviation - Amount of multimodal smearing to smooth out responses

distance_variance_penalty - A penalty to apply to a matched scan as it differs from the odometric pose

angle_variance_penalty - A penalty to apply to a matched scan as it differs from the odometric pose

fine_search_angle_offset - Range of angles to test for fine scan matching

coarse_search_angle_offset - Range of angles to test for coarse scan matching

coarse_angle_resolution - Resolution of angles over the Offset range to test in scan matching

minimum_angle_penalty - Smallest penalty an angle can have to ensure the size doesn't blow up

minimum_distance_penalty - Smallest penalty a scan can have to ensure the size doesn't blow up

use_response_expansion - Whether to automatically increase the search grid size if no viable match is found

Install

ROSDep will take care of the major things

rosdep install -q -y -r --from-paths src --ignore-src

Or install via apt

apt install ros-eloquent-slam-toolbox

Run your colcon build procedure of choice.

You can run via ros2 launch slam_toolbox online_sync_launch.py

Etc

NanoFlann!

In order to do some operations quickly for continued mapping and localization, I make liberal use of NanoFlann (shout out!).

Brief incursion into snaps

Snap are completely isolated containerized packages that one can run through the Canonical organization on a large number of Linux distributions. They're similar to Docker containers but it doesn't share the kernel or any of the libraries, and rather has everything internal as essentially a separate partitioned operating system based on Ubuntu Core.

We package up slam toolbox in this way for a nice multiple-on speed up in execution from a couple of pretty nuanced reasons in this particular project, but generally speaking you shouldn't expect a speedup from a snap.

Since Snaps are totally isolated and there's no override flags like in Docker, there's only a couple of fixed directories that both the snap and the host system can write and read from, including SNAP_COMMON (usually in /var/snap/[snap name]/common). Therefore, this is the place that if you're serializing and deserializing maps, you need to have them accessible to that directory.

You can optionally store all your serialized maps there, move maps there as needed, take maps from there after serialization, or do my favorite option and link the directories with ln to where ever you normally store your maps and you're wanting to dump your serialized map files.

Example of ln:

#           Source                           Linked
sudo ln -s /home/steve/maps/serialized_map/ /var/snap/slam-toolbox/common

and then all you have to do when you specify a map to use is set the filename to slam-toolbox/map_name and it should work no matter if you're running in a snap, docker, or on bare metal. The -s makes a symbol link so rather than /var/snap/slam-toolbox/common/* containing the maps, /var/snap/slam-toolbox/common/serialized_map/* will. By default on bare metal, the maps will be saved in .ros

More Gifs!

map_image

If someone from iRobot can use this to tell me my Roomba serial number by correlating to its maps, I'll buy them lunch and probably try to hire them.

slam_toolbox's People

Contributors

cottsay avatar dimasad avatar gene-su avatar hosseinsheikhi avatar ivonaj avatar james-ward avatar jsongcmu avatar kei1107 avatar lekoook avatar lucbettaieb avatar malban avatar maxlein avatar mgerdzhev avatar michael-equi avatar mikeferguson avatar msadowski avatar nhattanxt3 avatar nikolase avatar nkalupahana avatar oenzan avatar patricksowinski avatar pgotzmann avatar rayman avatar samiamlabs avatar shoemakerlevy9 avatar stevemacenski avatar tobias-fischer avatar traversaro avatar ubtjoe avatar v-lopez 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  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

slam_toolbox's Issues

Disappearing map?

Hi Steve!

Thanks for the great package! I'm currently running some tests and it's the first SLAM package I used that works very well out of the box.

It's very well possible that I've missed some parameter or something else in the docs but is the disappearing map the valid behaviour of slam_toolbox?

Here is how it looks like for me in the simulation (I believe I've seen it happened on real robot too):

slam_toolbox_map_erase

The map shown in the window above is the one appearing on map topic.

Any feedback you might have would be highly appreciated!

Snap store snap crashing in strict confinement

New to snap and this package so please forgive me but im getting this error whenever i try and run the snap version dev and regular.
process[sync_slam_toolbox_node-1]: started with pid [3374]
[ INFO] [1568987315.882619235]: Node using stack size 40000000
[FATAL] [1568987316.062751959]: Failed to create solver_plugins::CeresSolver, is it registered and built? Exception: Failed to load library /snap/slam-toolbox-melodic/3/opt/ros/melodic/lib/libceres_solver_plugin.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = liblapack.so.3: cannot open shared object file: No such file or directory).
[sync_slam_toolbox_node-1] process has died [pid 3374, exit code 1, cmd /snap/slam-toolbox-melodic/3/opt/ros/melodic/lib/slam_toolbox/sync_slam_toolbox_node __name:=sync_slam_toolbox_node __log:=/root/snap/slam-toolbox-melodic/3/ros/log/bddb5af8-dbab-11e9-9058-00155d011907/sync_slam_toolbox_node-1.log].
log file: /root/snap/slam-toolbox-melodic/3/ros/log/bddb5af8-dbab-11e9-9058-00155d011907/sync_slam_toolbox_node-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete

any help would be great as i expected the snap to just work and im not sure how to even get in there and mess with it.

roslaunch error

hello,
I'm very interested in ur package, and i can compile it successfully. but when i roslaunch slam_toolbox online_async.launch ,each launch file I tried.The error is
[slam_toolbox-2] process has died [pid 4758, exit code -11, cmd /home/gary/slam_toolbox_ws/install/lib/slam_toolbox/slam_toolbox __name:=slam_toolbox __log:=/home/gary/.ros/log/aa16d8b8-cc9b-11e9-980a-9cb6d06ccefb/slam_toolbox-2.log].
log file: /home/gary/.ros/log/aa16d8b8-cc9b-11e9-980a-9cb6d06ccefb/slam_toolbox-2*.log

I don't know what's going on? can u help me to work it out, thank u very much!

[Question]Dynamic environments

Hello, it is me again,
I would like to know if the system is able to cope with dynamic environments?
As an example i have a door that some times is open and some times closed and sometimes in the middle of the two.

The image below explains a little bit the situation.
image

Having a way to remove the old state of the door would help immensely for auto navigation.

custom lidar source: wrong number of "expected range readings"

Hi Steve,

I'm trying to use the software on a small home build diff drive robot. I'm using a X4 YDLIDAR and get the following message after starting the node:

process[slam_toolbox-1]: started with pid [14635]
[ INFO] [1566467601.227171238]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[ INFO] [1566467601.227750066]: Using plugin solver_plugins::CeresSolver
Info: clipped range threshold to be within minimum and maximum range!
Registering sensor: [Custom Described Lidar]
LaserRangeScan contains 720 range readings, expected 721

In the default configuration the laser /scan topic has the following header:

> rostopic echo --noarr /scan -n 1
header: 
  seq: 4756
  stamp: 
    secs: 1566468140
    nsecs: 604043000
  frame_id: "base_laser_link"
angle_min: -3.14159274101
angle_max: 3.14159274101
angle_increment: 0.00872664619237
time_increment: 0.000164166660397
scan_time: 0.11819999665
range_min: 0.10000000149
range_max: 16.0
ranges: "<array type: float32, length: 720>"
intensities: "<array type: float32, length: 720>"
---

If changing the lidar parameters e.g. min/max angle the expected number of readings differs always by one ...

catkin_make fails to build slam_toolbox in 16.04 docker image

Thanks for the great package!

When trying to build the toolbox during a docker image build, I receive the following output (and error):

Creating symlink "/home/slam/catkin_ws/src/CMakeLists.txt" pointing to "/opt/ros/kinetic/share/catkin
/cmake/toplevel.cmake"                                                                               
-- The C compiler identification is GNU 5.4.0                                                        
-- The CXX compiler identification is GNU 5.4.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/slam/catkin_ws/devel                                             
-- Using CMAKE_PREFIX_PATH: /opt/ros/kinetic                                                         
-- This workspace overlays: /opt/ros/kinetic                                                         
-- Found PythonInterp: /usr/bin/python (found version "2.7.12")                                      
-- Using PYTHON_EXECUTABLE: /usr/bin/python                                                          
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/slam/catkin_ws/build/test_results
-- Found gmock sources under '/usr/src/gmock': gmock will be built
-- 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/gmock': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.14
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~                                                 
-- ~~  traversing 1 packages in topological order:
-- ~~  - slam_toolbox
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'slam_toolbox'
-- ==> add_subdirectory(slam_toolbox)
-- Boost version: 1.58.0
-- Found the following Boost libraries:
--   system
--   serialization
--   filesystem
--   thread
--   chrono
--   date_time
--   atomic
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.1")
CMake Error at slam_toolbox/CMakeLists.txt:37 (find_package):
  By not providing "FindCSparse.cmake" in CMAKE_MODULE_PATH this project has
  asked CMake to find a package configuration file provided by "CSparse", but
  CMake did not find one.

  Could not find a package configuration file provided by "CSparse" with any
  of the following names:

    CSparseConfig.cmake
    csparse-config.cmake

  Add the installation prefix of "CSparse" to CMAKE_PREFIX_PATH or set
  "CSparse_DIR" to a directory containing one of the above files.  If
  "CSparse" provides a separate development package or SDK, be sure it has
  been installed.


-- Configuring incomplete, errors occurred!
See also "/home/slam/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/slam/catkin_ws/build/CMakeFiles/CMakeError.log".
Invoking "cmake" failed
Base path: /home/slam/catkin_ws
Source space: /home/slam/catkin_ws/src
Build space: /home/slam/catkin_ws/build
Devel space: /home/slam/catkin_ws/devel
Install space: /home/slam/catkin_ws/install
####
#### Running command: "cmake /home/slam/catkin_ws/src -DCATKIN_DEVEL_PREFIX=/home/slam/catkin_ws/deve
l -DCMAKE_INSTALL_PREFIX=/home/slam/catkin_ws/install -G Unix Makefiles" in "/home/slam/catkin_ws/build"
The command '/bin/bash -c source /opt/ros/kinetic/setup.bash     && cd /home/$username/catkin_ws/src
    && catkin_init_workspace     && cd ..     && catkin_make -j1' returned a non-zero code: 1

This appears to be a cmake issue, but I have checked that the FindCSparse.cmake file is indeed in $CMAKE_MODULE_PATH.

Here's the dockerfile:

FROM ros:kinetic-ros-base-xenial

ARG username=slam
ARG groupid=1000
ARG userid=1000

# USE BASH
SHELL ["/bin/bash", "-c"]

# RUN LINE BELOW TO REMOVE debconf ERRORS (MUST RUN BEFORE ANY apt-get CALLS)
RUN echo 'debconf debconf/frontend select Noninteractive' | debconf-set-selections

RUN apt-get update && apt-get install -y --no-install-recommends apt-utils
RUN apt-get install -y ros-kinetic-desktop-full

# setup user env at the end
# -m option creates a fake writable home folder
RUN adduser --disabled-password --gecos '' $username
RUN adduser $username sudo
RUN adduser $username dialout
RUN echo '%sudo ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers

# slam_toolbox
RUN mkdir -p /home/$username/catkin_ws/src \
    && chmod a+rwx /home/$username/catkin_ws \
    && chmod a+rwx /home/$username/catkin_ws/src
RUN cd /home/$username/catkin_ws/src && git clone https://github.com/SteveMacenski/slam_toolbox.git
RUN source /opt/ros/kinetic/setup.bash \
    && cd /home/$username/catkin_ws \
    && rosdep update \
    && rosdep install -q -y -r --from-paths src --ignore-src --rosdistro=kinetic -y

USER $username
RUN echo "source /opt/ros/kinetic/setup.bash" >> /home/$username/.bashrc

RUN source /opt/ros/kinetic/setup.bash \
    && cd /home/$username/catkin_ws/src \
    && catkin_init_workspace \
    && cd .. \
    && catkin_make -j1
RUN echo "source ~/catkin_ws/devel/setup.bash" >> /home/$username/.bashrc

WORKDIR /home/$username

I believe that there is something really stupid happening here, but I've yet to find it. Anyone have any ideas?

cannot localizaton just use localiztion.launch

hello,
sorry to bother u again.I tried the localization.launch file,and I changed the param "mode: localization" in .config file.but it doesn't work.it always do mapping without localization. my os is ubuntu16.04.

Include API in docs

What are the published topics/services, what are the subscribed topics/utilities

Add map_server as a dependency?

Hi Steven!

This one is trivial (happy to make a PR if needed!): currently map_server is not listed as a dependency and therefore a service call to "/serialize_map" can results in error if map_server was not manually installed.

Cleanup Code (dear god, its terrible)

  • pull out visualization stuff into separate class
  • call slam_toolbox library in application ROS level, too much is happening inline.
  • perhaps separate sync and async nodes
  • node bringup with a file to work with rather than a service
  • parameterize live slam w/ and w/o decay
  • messy node with everything but flexible, or changing between them cleanly

mapping failed (due to localization lost ?)

Hi!
I'm running into trouble during the mapping mode:
als long as the robot is moving straight forward or backward the mapping is fine but as soon as I add a rotation it seems that the localization gets more and more lost and therefore the mapping process will generate unusable maps.

I assume that I'm using a improper configuration and need some help ...

Here some information about the system:

  • diff drive robot
  • low cost YDLIDAR X4
    • mounted upside (rotation of scan unit is clockwise)
    • usage of latest software version V1.4.1
    • /scan topic header:
header: 
  seq: 192
  stamp: 
    secs: 1566986866
    nsecs:   8921560
  frame_id: "laser_link"
angle_min: -1.65806281567
angle_max: 1.65806281567
angle_increment: 0.00874967221171
time_increment: 0.00030976254493
scan_time: 0.117399998009
range_min: 0.10000000149
range_max: 16.0
ranges: "<array type: float32, length: 380>"
intensities: "<array type: float32, length: 380>"
---
  • tf tree:
    tf_tree

  • scans seems to be valid related to distance and angle in relation to laser_link:
    rviz_tf_scan

  • using latest version of slam_toolbox (6281c8c)

    • starting roslaunch slam_toolbox online_sync.launch
    • adjusting following parameters in config/mapper_params_online_sync.yaml:
      • base_frame: base_link
      • laser_frame: laser_link
      • max_laser_range: 16.0
    • running the node will give no error or warning messages:
process[sync_slam_toolbox_node-1]: started with pid [5404]
[ INFO] [1566983484.418758725]: Node using stack size 40000000
[ INFO] [1566983485.658208287]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[ INFO] [1566983485.658327096]: Using plugin solver_plugins::CeresSolver
Registering sensor: [Custom Described Lidar]
[ INFO] [1566983491.127153328]: Creating 1 swatches

Crash with sync_slam_toolbox_node: devel/lib/slam_toolbox/sync_slam_toolbox_node': free(): invalid pointer: 0x00007fe646ffc170 ***

Hi @SteveMacenski

Thanks for another great package! I'm in the process of trying it out and comparing it to Cartographer, but I'm running into some crashes when trying it out on some of my rosbags.

Summary:
I am on 16.04 / Kinetic, but I cloned melodic-devel and ran install deps / build without problems (at least any problems that I am aware of).

After modifying mapper_params_online_sync.yaml and online_sync.launch I can start the mapping process and have it run for a while, but at some point it crashes on all my bag files (different sensors / robots).

The error, as far as I can tell, summarizes to

`/ws/devel/lib/slam_toolbox/sync_slam_toolbox_node': free(): invalid pointer: 0x00007fe646ffc170 ***

I have yet to try async mode and see if the same thing happens there, and I haven't tried your snap either. I will try to do that in parallel with this issue being open.

If you need additional information feel free to ping me back. I look forward to trying out some of the interesting features when it no longer crashes :)

Full paste:
https://pastebin.com/Q7qM1jkZ

Highlights from crash:

process[sync_slam_toolbox_node-1]: started with pid [29140]
[ INFO] [1568978332.594228288]: Node using stack size 40000000
[ INFO] [1568978332.657693139]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[ INFO] [1568978332.657756921]: Using plugin solver_plugins::CeresSolver
Registering sensor: [Custom Described Lidar]

Solver Summary (v 1.13.0-eigen-(3.2.92)-lapack-suitesparse-(4.4.6)-cxsparse-(3.1.4)-openmp)

                                     Original                  Reduced
Parameter blocks                           84                       81
Parameters                                 84                       81
Residual blocks                            31                       31
Residual                                   93                       93

Minimizer                        TRUST_REGION

Sparse linear algebra library    SUITE_SPARSE
Trust region strategy     LEVENBERG_MARQUARDT

                                        Given                     Used
Linear solver          SPARSE_NORMAL_CHOLESKY   SPARSE_NORMAL_CHOLESKY
Threads                                    50                       50
Linear solver threads                       1                        1
Linear solver ordering              AUTOMATIC                       81

Cost:
Initial                          2.687018e+06
Final                            1.774825e+00
Change                           2.687016e+06

Minimizer iterations                        9
Successful steps                            9
Unsuccessful steps                          0

Time (in seconds):
Preprocessor                           0.0003

  Residual evaluation                  0.0069
  Jacobian evaluation                  0.0164
  Linear solver                        0.0009
Minimizer                              0.0248

Postprocessor                          0.0002
Total                                  0.0253

Termination:                      CONVERGENCE (Parameter tolerance reached. Relative step_norm: 8.743665e-04 <= 1.000000e-03.)

*** Error in `/home/x/RCW_workspaces/capra_ws/devel/lib/slam_toolbox/sync_slam_toolbox_node': free(): invalid pointer: 0x00007fe646ffc170 ***
======= Backtrace: =========
/lib/x86_64-linux-gnu/libc.so.6(+0x777e5)[0x7fe666cd07e5]
/lib/x86_64-linux-gnu/libc.so.6(+0x8037a)[0x7fe666cd937a]
/lib/x86_64-linux-gnu/libc.so.6(cfree+0x4c)[0x7fe666cdd53c]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZN9__gnu_cxx13new_allocatorIiE10deallocateEPim+0x20)[0x7fe65ce65b4c]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZNSt16allocator_traitsISaIiEE10deallocateERS0_Pim+0x2b)[0x7fe65ce63594]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZNSt12_Vector_baseIiSaIiEE13_M_deallocateEPim+0x32)[0x7fe65ce6122c]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZNSt12_Vector_baseIiSaIiEED2Ev+0x41)[0x7fe65ce5e85f]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZNSt6vectorIiSaIiEED1Ev+0x41)[0x7fe65ce5c7b3]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZN5ceres6Solver7SummaryD2Ev+0x1e)[0x7fe65ce5ae94]
/home/x/RCW_workspaces/capra_ws/devel/lib/libceres_solver_plugin.so(_ZN14solver_plugins11CeresSolver7ComputeEv+0x7f5)[0x7fe65ce5537f]
======= Memory map: ========
00400000-0053b000 r-xp 00000000 08:05 425235                             /home/x/RCW_workspaces/capra_ws/devel/.private/slam_toolbox/lib/slam_toolbox/sync_slam_toolbox_node
0073a000-0073b000 r--p 0013a000 08:05 425235                             /home/x/RCW_workspaces/capra_ws/devel/.private/slam_toolbox/lib/slam_toolbox/sync_slam_toolbox_node
0073b000-0073c000 rw-p 0013b000 08:05 425235                             /home/x/RCW_workspaces/capra_ws/devel/.private/slam_toolbox/lib/slam_toolbox/sync_slam_toolbox_node
0073c000-0073d000 rw-p 00000000 00:00 0 
02504000-02975000 rw-p 00000000 00:00 0                                 
 [heap]
...
 [stack]
...
[sync_slam_toolbox_node-1] process has died [pid 29140, exit code -6, cmd /home/x/RCW_workspaces/capra_ws/devel/lib/slam_toolbox/sync_slam_toolbox_node scan:=/os1/scan odom:=/camera/odom/sample __name:=sync_slam_toolbox_node __log:=/home/x/.ros/log/76759c88-db82-11e9-89d9-1c1bb5890ad0/sync_slam_toolbox_node-1.log].
log file: /home/x/.ros/log/76759c88-db82-11e9-89d9-1c1bb5890ad0/sync_slam_toolbox_node-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Refine experimental lifelong mapping to production

  • pluginlib objective functions for others to define new and interesting scoring methods that is at the heart of it
  • refine objective function to use the number of candidates or graph structure
  • necessity to transfer constraints of nodes once decayed
    -- Additional ideas: before decay check for cycles or that removing it won't fragment the graph, and then transfer the constraints to retain that structure
    -- Look at optimizer output to see if structure is lost after removal
    -- See how Ceres scales with Nodes with fixed # constraints, and the constraints with fixed number of nodes
    -- transfer only some constraints, or only constraints from a loop closure

Add gifs to readme

  • collect initial data from space worth displaying (full, use partial for continue and full for localization demos)
  • collect another set on another day for continuing / localization demos
  • create mapping image and gif. Create continue mapping gif, create localization gif

Proper usage of `save_map` service?

Hey @SteveMacenski ,

While observing mapping data from my robot (which is running as the ros master) I am trying to save the map (on my laptop) with the following call:

rosservice call /sync_slam_toolbox_node/save_map "name:
  data: './map.pgm'"

and the behavior is quite bizarre. Sometimes the command hangs and sometimes it completes but there is no map.pgm file anywhere to be found. Meanwhile, rosrun map_server map_saver does exactly what I want.

You mention in the README that the aforementioned service is just a wrapper for map_saver, but this doesn't appear to be the case. Any thoughts?

Memory and CPU benchmarking

See where the memory is, where the CPU time is, and how to reduce. Long term (days) dataset hardening. Check for leaks

graph memory / cpu usage over a 3 hour dataset mapping, localizing

Reduce footprint by vector->map for m_scans and m_vertices and dataset that scale to size N but full of null pointers -- replace checks for null with find query failure. Also a faster lookup for maps > 30 nodes (so like... all of them)

ROS2 port

  • port code (pending: interactive marker stuff, rviz plugin, config, launch)
  • update links for build farm / docker
  • build farm PR builder / CI
  • release
  • test test test
  • see if automated tests work
  • update config files and launch files

known things to circle back

  • interactive markers arent ported to ROS2
  • toMsg for transform stamped isnt working, had to patch
  • ros2 stack paramter being read in and not causing issues

Question about integrating IMU and Odometry sources

Hello,

This is a great package, and we are learning how to use it at its full extent.

We want to know which are the best practices (and if there are examples) on using IMUs and odometry sources (wheels or realsens T265). Is it straight up like remapping the topic to 'shape it' for slam toolbox? Or do we need to use an external package like robot localisation to do it effectively.

Many thanks for the help :)

Pepe

Show demo of multirobot cloud mapping

Each laserrangefinder object needs its own odometry storage (last_odom[finder]) for calculating the constraint in the SDK. I think that's really the only big thing needed on top of the multi-laser work done, they just need to have unique names now (have some frame info given out, see multi-laser branch)

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.