Skip to content
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

Midigate spamming for 50Hz lidar #526

Merged
merged 2 commits into from
Aug 24, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -222,6 +222,8 @@ The following settings and options are exposed to you. My default configuration

`scan_topic` - scan topic, *absolute* path, ei `/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

`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
Expand Down
2 changes: 1 addition & 1 deletion include/slam_toolbox/slam_toolbox_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ class SlamToolbox : public rclcpp::Node
std::string odom_frame_, map_frame_, base_frame_, map_name_, scan_topic_;
rclcpp::Duration transform_timeout_, minimum_time_interval_;
std_msgs::msg::Header scan_header;
int throttle_scans_;
int throttle_scans_, scan_queue_size_;

double resolution_;
double position_covariance_scale_;
Expand Down
5 changes: 4 additions & 1 deletion src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,9 @@ void SlamToolbox::setParams()
scan_topic_ = std::string("/scan");
scan_topic_ = this->declare_parameter("scan_topic", scan_topic_);

scan_queue_size_ = 1.0;
scan_queue_size_ = this->declare_parameter("scan_queue_size", scan_queue_size_);

throttle_scans_ = 1;
throttle_scans_ = this->declare_parameter("throttle_scans", throttle_scans_);

Expand Down Expand Up @@ -217,7 +220,7 @@ void SlamToolbox::setROSInterfaces()
shared_from_this().get(), scan_topic_, rmw_qos_profile_sensor_data);
scan_filter_ =
std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*scan_filter_sub_, *tf_, odom_frame_, 1, shared_from_this(),
*scan_filter_sub_, *tf_, odom_frame_, scan_queue_size_, shared_from_this(),
tf2::durationFromSec(transform_timeout_.seconds()));
scan_filter_->registerCallback(
std::bind(&SlamToolbox::laserCallback, this, std::placeholders::_1));
Expand Down