-
Notifications
You must be signed in to change notification settings - Fork 644
add param to config files, mutex locks, stack size fix #8
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
add param to config files, mutex locks, stack size fix #8
Conversation
| use_response_expansion: true | ||
|
|
||
| # Load Map Parameters | ||
| inverted_laser: true No newline at end of file |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
missing laser frame?
| use_response_expansion: true | ||
|
|
||
| # Load Map Parameters | ||
| inverted_laser: true No newline at end of file |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
missing laser frame?
src/slam_toolbox.cpp
Outdated
| { | ||
| ros::init(argc, argv, "slam_toolbox"); | ||
| ros::NodeHandle nh; | ||
| const rlim_t max_stack_size = 16777216; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
... what's this magic number? can't we round to something nice, say 20MB
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
and add as a top preprocessor variable. #define max_stack_size 20000000 //comment explaining
* Add graph edges to graph visualization marker. (SteveMacenski#502) * Clear markers for graph visualization to account for removed nodes. (SteveMacenski#503) * Publish PoseWithCovarianceStamped message with each scan match. (SteveMacenski#504) * Publish PoseWithCovarianceStamped message with each scan match. * Refactor code to return covariance as a output parameter instead of storing in the range scan object. * Linting fixes. * Publish pose with covariance in localization mode. (SteveMacenski#508) * Visualize localization nodes and edges with different colors in the pose graph marker message. (SteveMacenski#509) * Add map_and_localization node that supports toggling between mapping and localization modes with a service. (SteveMacenski#510) * Stop ceres problem from freeing loss function (SteveMacenski#519) (SteveMacenski#520) Co-authored-by: john-maidbot <78750993+john-maidbot@users.noreply.github.com> * Experimental changes. * Initial experiments (pose w cov stamped for each scan msg, better graph edge vis, tweak to continuous scan matching, etc) (SteveMacenski#2) * Add option to perform continuous scan matching to update the transform and pose even when the minimum travel distance or heading have not been reached for adding the scan into the map. * Add graph edges to graph visualization marker. (SteveMacenski#502) * Clear markers for graph visualization to account for removed nodes. (SteveMacenski#503) * Publish PoseWithCovarianceStamped message with each scan match. (SteveMacenski#504) * Publish PoseWithCovarianceStamped message with each scan match. * Refactor code to return covariance as a output parameter instead of storing in the range scan object. * Linting fixes. * Tweaks to parameter documentation. * Refactor scan match only logic to be based on a time interval. * Need to install async_pruned_slam_toolbox lib * Add localization status publisher (SteveMacenski#3) * Lint slam_toolbox_async_pruned.cpp * Change a lot of INFO prints related to pruning to DEBUG * Modified pause behavior. Added start/stop services and reset functionality. (SteveMacenski#5) * Modified pause behavior. Added reset service * One last book keeping issue. Dont publish graph without subscribers * Add start/stop service * Enable switching from mapping to localization mode (SteveMacenski#6) * Lidar qos is sensor data (best effort) (SteveMacenski#7) * Lidar qos is sensor data (best effort) * typo * Set initial slam pose via subscription (SteveMacenski#8) * Freeze map nodes when localizing + don't partition the graph when popping localization nodes + don't crash when resetting in localization mode (SteveMacenski#9) * Set non-localization nodes to constant * Forbid removing localization nodes if we don't have enough connections to the map graph * Fix crash on reset * unfreeze nodes when exiting localization mode * Don't freeze nodes that aren't part of the problem yet * Merge fixes. * Support resetting mapping pose. Co-authored-by: Marc Alban <marcalban@gmail.com> Co-authored-by: Marc Alban <marcalban@hatchbed.com> Co-authored-by: Justin Nguyen <justin@maidbot.com> Co-authored-by: Ketan Kharche <47426551+ketan-maidbot@users.noreply.github.com>
* Use new tf2 listener constructor * Update
…anup Mapping cleanup
Refactor slam_toolbox_common.hpp to initialize update_map_once_ flag …
* remove pose2D (#8) Remove pose2D follwing Remove Pose2D deprecation, No conflicts * change initialize part:geometry_msgs::msg::Pose() --------- Co-authored-by: hyunsehyun <wjwjwj20002@gachon.ac.kr>
No description provided.