Adds lua parameter for setting transform wait time (#33)

master
Stefan Kohlbrecher 2016-08-30 11:31:54 +02:00 committed by Damon Kohler
parent 76b1f92fcd
commit 058958e38c
4 changed files with 7 additions and 2 deletions

View File

@ -26,6 +26,7 @@ options = {
laser_min_range = 0., laser_min_range = 0.,
laser_max_range = 30., laser_max_range = 30.,
laser_missing_echo_ray_length = 5., laser_missing_echo_ray_length = 5.,
lookup_transform_timeout = 0.01,
use_multi_echo_laser_scan_2d = true use_multi_echo_laser_scan_2d = true
} }

View File

@ -26,6 +26,7 @@ options = {
laser_min_range = 0., laser_min_range = 0.,
laser_max_range = 30., laser_max_range = 30.,
laser_missing_echo_ray_length = 5., laser_missing_echo_ray_length = 5.,
lookup_transform_timeout = 0.01,
num_lasers_3d = 2 num_lasers_3d = 2
} }

View File

@ -26,6 +26,7 @@ options = {
laser_min_range = 0., laser_min_range = 0.,
laser_max_range = 30., laser_max_range = 30.,
laser_missing_echo_ray_length = 5., laser_missing_echo_ray_length = 5.,
lookup_transform_timeout = 0.01,
use_laser_scan_2d = true use_laser_scan_2d = true
} }

View File

@ -94,7 +94,6 @@ constexpr int64 kTrajectoryId = 0;
constexpr int kSubscriberQueueSize = 150; constexpr int kSubscriberQueueSize = 150;
constexpr int kSubmapPublishPeriodInUts = 300 * 10000ll; // 300 milliseconds constexpr int kSubmapPublishPeriodInUts = 300 * 10000ll; // 300 milliseconds
constexpr int kPosePublishPeriodInUts = 5 * 10000ll; // 5 milliseconds constexpr int kPosePublishPeriodInUts = 5 * 10000ll; // 5 milliseconds
constexpr double kMaxTransformDelaySeconds = 0.01;
constexpr double kSensorDataRatesLoggingPeriodSeconds = 15.; constexpr double kSensorDataRatesLoggingPeriodSeconds = 15.;
// Unique default topic names. Expected to be remapped as needed. // Unique default topic names. Expected to be remapped as needed.
@ -248,6 +247,7 @@ class Node {
double laser_min_range_; double laser_min_range_;
double laser_max_range_; double laser_max_range_;
double laser_missing_echo_ray_length_; double laser_missing_echo_ray_length_;
double lookup_transform_timeout_;
tf2_ros::Buffer tf_buffer_; tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_; tf2_ros::TransformListener tf_;
@ -282,7 +282,7 @@ Rigid3d Node::LookupToTrackingTransformOrThrow(const carto::common::Time time,
const string& frame_id) { const string& frame_id) {
return ToRigid3d( 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(lookup_transform_timeout_)));
} }
void Node::OdometryMessageCallback(const nav_msgs::Odometry::ConstPtr& msg) { void Node::OdometryMessageCallback(const nav_msgs::Odometry::ConstPtr& msg) {
@ -416,6 +416,8 @@ void Node::Initialize() {
laser_max_range_ = lua_parameter_dictionary.GetDouble("laser_max_range"); laser_max_range_ = lua_parameter_dictionary.GetDouble("laser_max_range");
laser_missing_echo_ray_length_ = laser_missing_echo_ray_length_ =
lua_parameter_dictionary.GetDouble("laser_missing_echo_ray_length"); lua_parameter_dictionary.GetDouble("laser_missing_echo_ray_length");
lookup_transform_timeout_ =
lua_parameter_dictionary.GetDouble("lookup_transform_timeout");
// Set of all topics we subscribe to. We use the non-remapped default names // Set of all topics we subscribe to. We use the non-remapped default names
// which are unique. // which are unique.