Rename and cleanup. (#4)

Merges 3d_mapping.lua into backpack_3d.lua. Renames launch files to be
consistent. Fixes a typo.
master
Wolfgang Hess 2016-08-04 10:04:53 +02:00 committed by GitHub
parent 558768f4e3
commit b89d9a51a5
5 changed files with 5 additions and 22 deletions

View File

@ -1,19 +0,0 @@
-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
-- http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.
include "backpack_3d.lua"
options.trajectory_builder.scans_per_accumulation = 2
return options

View File

@ -29,4 +29,6 @@ options.sparse_pose_graph.constraint_builder.adaptive_voxel_filter = TRAJECTORY_
options.sparse_pose_graph.constraint_builder.min_score = 0.62 options.sparse_pose_graph.constraint_builder.min_score = 0.62
options.sparse_pose_graph.constraint_builder.log_matches = true options.sparse_pose_graph.constraint_builder.log_matches = true
options.trajectory_builder.scans_per_accumulation = 2
return options return options

View File

@ -90,7 +90,7 @@
configuration_files_directories: [ configuration_files_directories: [
"$(find cartographer_ros)/configuration_files" "$(find cartographer_ros)/configuration_files"
] ]
mapping_configuration_basename: "3d_mapping.lua" mapping_configuration_basename: "backpack_3d.lua"
imu_topic: "/imu" imu_topic: "/imu"
laser_scan_3d_topics: ["/horizontal_3d_laser", "/vertical_3d_laser"] laser_scan_3d_topics: ["/horizontal_3d_laser", "/vertical_3d_laser"]
laser_min_range_m: 0. laser_min_range_m: 0.

View File

@ -80,7 +80,7 @@ constexpr int kSubmapPublishPeriodInUts = 300 * 10000ll; // 300 milliseconds
constexpr int kPosePublishPeriodInUts = 5 * 10000ll; // 5 milliseconds constexpr int kPosePublishPeriodInUts = 5 * 10000ll; // 5 milliseconds
constexpr double kMaxTransformDelaySeconds = 1.; constexpr double kMaxTransformDelaySeconds = 1.;
Rigid3d ToRidig3d(const geometry_msgs::TransformStamped& transform) { Rigid3d ToRigid3d(const geometry_msgs::TransformStamped& transform) {
return Rigid3d(Eigen::Vector3d(transform.transform.translation.x, return Rigid3d(Eigen::Vector3d(transform.transform.translation.x,
transform.transform.translation.y, transform.transform.translation.y,
transform.transform.translation.z), transform.transform.translation.z),
@ -220,7 +220,7 @@ Node::Node()
Rigid3d Node::LookupToTrackingTransformOrThrow( Rigid3d Node::LookupToTrackingTransformOrThrow(
const ::cartographer::common::Time time, const string& frame_id) { const ::cartographer::common::Time time, const string& frame_id) {
return ToRidig3d( return ToRigid3d(
tf_buffer_.lookupTransform(tracking_frame_, frame_id, ToRos(time), tf_buffer_.lookupTransform(tracking_frame_, frame_id, ToRos(time),
ros::Duration(kMaxTransformDelaySeconds))); ros::Duration(kMaxTransformDelaySeconds)));
} }