Injects tf buffer into Node. (#200)
parent
6260c53107
commit
c57075f67d
|
@ -46,7 +46,6 @@ namespace carto = ::cartographer;
|
|||
using carto::transform::Rigid3d;
|
||||
|
||||
constexpr int kLatestOnlyPublisherQueueSize = 1;
|
||||
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
|
||||
|
||||
// Default topic names; expected to be remapped as needed.
|
||||
constexpr char kOccupancyGridTopic[] = "map";
|
||||
|
@ -54,11 +53,9 @@ constexpr char kScanMatchedPointCloudTopic[] = "scan_matched_points2";
|
|||
constexpr char kSubmapListTopic[] = "submap_list";
|
||||
constexpr char kSubmapQueryServiceName[] = "submap_query";
|
||||
|
||||
Node::Node(const NodeOptions& options)
|
||||
Node::Node(const NodeOptions& options, tf2_ros::Buffer* const tf_buffer)
|
||||
: options_(options),
|
||||
tf_buffer_(::ros::Duration(kTfBufferCacheTimeInSeconds)),
|
||||
tf_(tf_buffer_),
|
||||
map_builder_bridge_(options_, &tf_buffer_) {}
|
||||
map_builder_bridge_(options_, tf_buffer) {}
|
||||
|
||||
Node::~Node() {
|
||||
{
|
||||
|
|
|
@ -30,14 +30,13 @@
|
|||
#include "cartographer_ros_msgs/TrajectorySubmapList.h"
|
||||
#include "ros/ros.h"
|
||||
#include "tf2_ros/transform_broadcaster.h"
|
||||
#include "tf2_ros/transform_listener.h"
|
||||
|
||||
namespace cartographer_ros {
|
||||
|
||||
// Wires up ROS topics to SLAM.
|
||||
class Node {
|
||||
public:
|
||||
Node(const NodeOptions& options);
|
||||
Node(const NodeOptions& options, tf2_ros::Buffer* tf_buffer);
|
||||
~Node();
|
||||
|
||||
Node(const Node&) = delete;
|
||||
|
@ -60,8 +59,6 @@ class Node {
|
|||
|
||||
const NodeOptions options_;
|
||||
|
||||
tf2_ros::Buffer tf_buffer_;
|
||||
tf2_ros::TransformListener tf_;
|
||||
tf2_ros::TransformBroadcaster tf_broadcaster_;
|
||||
|
||||
cartographer::common::Mutex mutex_;
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include "cartographer/common/port.h"
|
||||
#include "cartographer_ros/node.h"
|
||||
#include "cartographer_ros/ros_log_sink.h"
|
||||
#include "tf2_ros/transform_listener.h"
|
||||
|
||||
DEFINE_string(configuration_directory, "",
|
||||
"First directory in which configuration files are searched, "
|
||||
|
@ -55,7 +56,10 @@ void Run() {
|
|||
code, std::move(file_resolver));
|
||||
|
||||
const auto options = CreateNodeOptions(&lua_parameter_dictionary);
|
||||
Node node(options);
|
||||
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
|
||||
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
||||
tf2_ros::TransformListener tf(tf_buffer);
|
||||
Node node(options, &tf_buffer);
|
||||
|
||||
int trajectory_id = -1;
|
||||
std::unordered_set<string> expected_sensor_ids;
|
||||
|
|
Loading…
Reference in New Issue