New Cartographer API. (#157)
parent
22d8573bd0
commit
2ec6001f96
|
@ -40,13 +40,6 @@ const string& CheckNoLeadingSlash(const string& frame_id) {
|
|||
SensorBridgeOptions CreateSensorBridgeOptions(
|
||||
carto::common::LuaParameterDictionary* const lua_parameter_dictionary) {
|
||||
SensorBridgeOptions options;
|
||||
options.horizontal_laser_min_range =
|
||||
lua_parameter_dictionary->GetDouble("horizontal_laser_min_range");
|
||||
options.horizontal_laser_max_range =
|
||||
lua_parameter_dictionary->GetDouble("horizontal_laser_max_range");
|
||||
options.horizontal_laser_missing_echo_ray_length =
|
||||
lua_parameter_dictionary->GetDouble(
|
||||
"horizontal_laser_missing_echo_ray_length");
|
||||
options.constant_odometry_translational_variance =
|
||||
lua_parameter_dictionary->GetDouble(
|
||||
"constant_odometry_translational_variance");
|
||||
|
@ -137,10 +130,11 @@ void SensorBridge::HandlePointCloud2Message(
|
|||
void SensorBridge::HandleLaserScanProto(
|
||||
const string& topic, const carto::common::Time time, const string& frame_id,
|
||||
const carto::sensor::proto::LaserScan& laser_scan) {
|
||||
const auto laser_fan = carto::sensor::ToLaserFan(
|
||||
laser_scan, options_.horizontal_laser_min_range,
|
||||
options_.horizontal_laser_max_range,
|
||||
options_.horizontal_laser_missing_echo_ray_length);
|
||||
const carto::sensor::LaserFan laser_fan = {
|
||||
Eigen::Vector3f::Zero(),
|
||||
carto::sensor::ToPointCloud(laser_scan),
|
||||
{},
|
||||
{}};
|
||||
const auto sensor_to_tracking =
|
||||
tf_bridge_->LookupToTracking(time, CheckNoLeadingSlash(frame_id));
|
||||
if (sensor_to_tracking != nullptr) {
|
||||
|
|
|
@ -33,9 +33,6 @@
|
|||
namespace cartographer_ros {
|
||||
|
||||
struct SensorBridgeOptions {
|
||||
double horizontal_laser_min_range;
|
||||
double horizontal_laser_max_range;
|
||||
double horizontal_laser_missing_echo_ray_length;
|
||||
double constant_odometry_translational_variance;
|
||||
double constant_odometry_rotational_variance;
|
||||
};
|
||||
|
|
|
@ -17,9 +17,6 @@ include "map_builder.lua"
|
|||
options = {
|
||||
map_builder = MAP_BUILDER,
|
||||
sensor_bridge = {
|
||||
horizontal_laser_min_range = 0.,
|
||||
horizontal_laser_max_range = 30.,
|
||||
horizontal_laser_missing_echo_ray_length = 5.,
|
||||
constant_odometry_translational_variance = 0.,
|
||||
constant_odometry_rotational_variance = 0.,
|
||||
},
|
||||
|
|
|
@ -17,9 +17,6 @@ include "map_builder.lua"
|
|||
options = {
|
||||
map_builder = MAP_BUILDER,
|
||||
sensor_bridge = {
|
||||
horizontal_laser_min_range = 0.,
|
||||
horizontal_laser_max_range = 30.,
|
||||
horizontal_laser_missing_echo_ray_length = 5.,
|
||||
constant_odometry_translational_variance = 0.,
|
||||
constant_odometry_rotational_variance = 0.,
|
||||
},
|
||||
|
|
|
@ -17,9 +17,6 @@ include "map_builder.lua"
|
|||
options = {
|
||||
map_builder = MAP_BUILDER,
|
||||
sensor_bridge = {
|
||||
horizontal_laser_min_range = 0.,
|
||||
horizontal_laser_max_range = 30.,
|
||||
horizontal_laser_missing_echo_ray_length = 5.,
|
||||
constant_odometry_translational_variance = 0.,
|
||||
constant_odometry_rotational_variance = 0.,
|
||||
},
|
||||
|
@ -38,10 +35,12 @@ options = {
|
|||
}
|
||||
|
||||
MAP_BUILDER.use_trajectory_builder_2d = true
|
||||
|
||||
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
|
||||
TRAJECTORY_BUILDER_2D.use_imu_data = false
|
||||
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
|
||||
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
|
||||
|
||||
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
||||
|
||||
return options
|
||||
|
|
|
@ -17,9 +17,6 @@ include "map_builder.lua"
|
|||
options = {
|
||||
map_builder = MAP_BUILDER,
|
||||
sensor_bridge = {
|
||||
horizontal_laser_min_range = 0.3,
|
||||
horizontal_laser_max_range = 8.,
|
||||
horizontal_laser_missing_echo_ray_length = 1.,
|
||||
constant_odometry_translational_variance = 0.,
|
||||
constant_odometry_rotational_variance = 0.,
|
||||
},
|
||||
|
@ -38,8 +35,13 @@ options = {
|
|||
}
|
||||
|
||||
MAP_BUILDER.use_trajectory_builder_2d = true
|
||||
|
||||
TRAJECTORY_BUILDER_2D.laser_min_range = 0.3,
|
||||
TRAJECTORY_BUILDER_2D.laser_max_range = 8.,
|
||||
TRAJECTORY_BUILDER_2D.laser_missing_echo_ray_length = 1.,
|
||||
TRAJECTORY_BUILDER_2D.use_imu_data = false
|
||||
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
|
||||
|
||||
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
||||
|
||||
return options
|
||||
|
|
|
@ -71,16 +71,6 @@ use_horizontal_multi_echo_laser
|
|||
"echoes" topic. If 2D SLAM is used, either this or *use_horizontal_laser*
|
||||
must be enabled.
|
||||
|
||||
sensor_bridge.horizontal_laser_min_range
|
||||
Range in meters below which laser returns are ignored for the purpose of SLAM.
|
||||
|
||||
sensor_bridge.horizontal_laser_max_range
|
||||
Range in meters above which laser returns are ignored for the purpose of SLAM.
|
||||
|
||||
sensor_bridge.horizontal_laser_missing_echo_ray_length
|
||||
Range in meters to use for inserting free space when no laser return was
|
||||
detected.
|
||||
|
||||
num_lasers_3d
|
||||
Number of 3D lasers to subscribe to. Must be a positive value if and only if
|
||||
using 3D SLAM. Subscribes to `sensor_msgs/PointCloud2`_ on the "points2"
|
||||
|
|
Loading…
Reference in New Issue