Skip to content
This repository was archived by the owner on Sep 13, 2022. It is now read-only.
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
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,10 @@
#ifndef DEPTHIMAGE_TO_POINTCLOUD2__DEPTH_TRAITS_HPP_
#define DEPTHIMAGE_TO_POINTCLOUD2__DEPTH_TRAITS_HPP_

#include <stdint.h>

#include <algorithm>
#include <cmath>
#include <limits>
#include <vector>

Expand Down
17 changes: 12 additions & 5 deletions turtlebot2_cartographer/configuration_files/turtlebot_2d.lua
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,19 @@ options = {
odom_frame = "odom",
provide_odom_frame = false,
use_odometry = true,
use_laser_scan = true,
use_multi_echo_laser_scan = false,
-- use_laser_scan = true,
num_laser_scans = 1,
-- use_multi_echo_laser_scan = false,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
rangefinder_sampling_ratio = 1.0,
odometry_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true
Expand All @@ -46,8 +53,8 @@ TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 300

TRAJECTORY_BUILDER_2D.submaps.resolution = 0.035
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 120
SPARSE_POSE_GRAPH.optimize_every_n_scans = 120
SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.82
SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 1.
POSE_GRAPH.optimize_every_n_nodes = 120
POSE_GRAPH.constraint_builder.min_score = 0.82
POSE_GRAPH.constraint_builder.sampling_ratio = 1.

return options
25 changes: 15 additions & 10 deletions turtlebot2_cartographer/configuration_files/turtlebot_3d.lua
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,15 @@ options = {
use_odometry = true,
use_laser_scan = false,
use_multi_echo_laser_scan = false,
num_subdivisions_per_laser_scan = 1,
num_laser_scans = 0,
num_point_clouds = 1,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
rangefinder_sampling_ratio = 1.0,
odometry_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_3d = true
Expand All @@ -56,16 +61,16 @@ TRAJECTORY_BUILDER_3D.ceres_scan_matcher.rotation_weight = 1e3
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.only_optimize_yaw = true
TRAJECTORY_BUILDER_3D.kalman_local_trajectory_builder.scan_matcher_variance = 1e-8

SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 0.2
SPARSE_POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
SPARSE_POSE_GRAPH.constraint_builder.adaptive_voxel_filter = TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter
SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.48
SPARSE_POSE_GRAPH.constraint_builder.log_matches = true
SPARSE_POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_rotational_score = 0.
SPARSE_POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_xy_search_window = 2.
POSE_GRAPH.constraint_builder.sampling_ratio = 0.2
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
POSE_GRAPH.constraint_builder.adaptive_voxel_filter = TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter
POSE_GRAPH.constraint_builder.min_score = 0.48
POSE_GRAPH.constraint_builder.log_matches = true
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_rotational_score = 0.
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_xy_search_window = 2.

SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e1
SPARSE_POSE_GRAPH.optimization_problem.acceleration_weight = 1e-1
SPARSE_POSE_GRAPH.optimization_problem.rotation_weight = 1e3
POSE_GRAPH.optimization_problem.huber_scale = 1e1
POSE_GRAPH.optimization_problem.acceleration_weight = 1e-1
POSE_GRAPH.optimization_problem.rotation_weight = 1e3

return options
3 changes: 2 additions & 1 deletion turtlebot2_drivers/src/kobuki_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,13 @@

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated"
# pragma GCC diagnostic ignored "-Wignored-qualifiers"
# pragma GCC diagnostic ignored "-Wsign-compare"
# pragma GCC diagnostic ignored "-Wstrict-aliasing"
# pragma GCC diagnostic ignored "-Wunused-local-typedefs"
# pragma GCC diagnostic ignored "-Wunused-parameter"
# pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#endif
#include "kobuki_driver/kobuki.hpp"
#ifndef _WIN32
Expand Down Expand Up @@ -81,7 +83,6 @@ int main(int argc, char * argv[])

auto node = rclcpp::Node::make_shared("kobuki_node");
g_logger = node->get_logger();
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto cmd_vel_sub = node->create_subscription<geometry_msgs::msg::Twist>(
"cmd_vel", cmdVelCallback, cmd_vel_qos_profile);
auto odom_pub = node->create_publisher<nav_msgs::msg::Odometry>("odom", odom_and_imu_qos_profile);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,12 @@
#ifndef DEPTH_IMAGE_PROC_DEPTH_TRAITS
#define DEPTH_IMAGE_PROC_DEPTH_TRAITS

#include <stdint.h>

#include <algorithm>
#include <cmath>
#include <limits>
#include <vector>

namespace depth_image_proc {

Expand Down
1 change: 1 addition & 0 deletions turtlebot2_follower/src/follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
// This file is originally from:
// https://github.com/turtlebot/turtlebot_apps/blob/cefaf0a/turtlebot_follower/src/follower.cpp

#include <cmath>
#include <vector>

#include <rclcpp/rclcpp.hpp>
Expand Down