Namespaces | Functions | Variables
offline_node.cc File Reference
#include "cartographer_ros/offline_node.h"
#include <errno.h>
#include <string.h>
#include <sys/resource.h>
#include <time.h>
#include <chrono>
#include "absl/strings/str_split.h"
#include "cartographer_ros/node.h"
#include "cartographer_ros/playable_bag.h"
#include "cartographer_ros/urdf_reader.h"
#include "gflags/gflags.h"
#include "ros/callback_queue.h"
#include "rosgraph_msgs/Clock.h"
#include "tf2_ros/static_transform_broadcaster.h"
#include "urdf/model.h"
Include dependency graph for offline_node.cc:

Go to the source code of this file.

Namespaces

namespace  cartographer_ros

Functions

 DEFINE_bool (collect_metrics, false,"Activates the collection of runtime metrics. If activated, the ""metrics can be accessed via a ROS service.")
 DEFINE_bool (use_bag_transforms, true,"Whether to read, use and republish transforms from bags.")
 DEFINE_bool (load_frozen_state, true,"Load the saved state as frozen (non-optimized) trajectories.")
 DEFINE_bool (keep_running, false,"Keep running the offline node after all messages from the bag ""have been processed.")
 DEFINE_double (skip_seconds, 0,"Optional amount of seconds to skip from the beginning ""(i.e. when the earliest bag starts.). ")
 DEFINE_string (configuration_directory,"","First directory in which configuration files are searched, ""second is always the Cartographer installation to allow ""including files from there.")
 DEFINE_string (configuration_basenames,"","Comma-separated list of basenames, i.e. not containing any ""directory prefix, of the configuration files for each trajectory. ""The first configuration file will be used for node options. ""If less configuration files are specified than trajectories, the ""first file will be used the remaining trajectories.")
 DEFINE_string (bag_filenames,"","Comma-separated list of bags to process. One bag per trajectory. ""Any combination of simultaneous and sequential bags is supported.")
 DEFINE_string (urdf_filenames,"","Comma-separated list of one or more URDF files that contain ""static links for the sensor configuration(s).")
 DEFINE_string (load_state_filename,"","If non-empty, filename of a .pbstream file to load, containing ""a saved SLAM state.")
 DEFINE_string (save_state_filename,"","Explicit name of the file to which the serialized state will be ""written before shutdown. If left empty, the filename will be ""inferred from the first bagfile's name as: ""<bag_filenames[0]>.pbstream")
void cartographer_ros::RunOfflineNode (const MapBuilderFactory &map_builder_factory)

Variables

constexpr double cartographer_ros::kClockPublishFrequencySec = 1. / 30.
constexpr char cartographer_ros::kClockTopic [] = "clock"
const ::ros::Duration cartographer_ros::kDelay = ::ros::Duration(1.0)
constexpr int cartographer_ros::kSingleThreaded = 1
constexpr char cartographer_ros::kTfStaticTopic [] = "/tf_static"
constexpr char cartographer_ros::kTfTopic [] = "tf"

Function Documentation

DEFINE_bool ( collect_metrics  ,
false  ,
"Activates the collection of runtime metrics. If  activated,
the""metrics can be accessed via a ROS service."   
)
DEFINE_bool ( use_bag_transforms  ,
true  ,
"Whether to  read,
use and republish transforms from bags."   
)
DEFINE_bool ( load_frozen_state  ,
true  ,
"Load the saved state as frozen (non-optimized) trajectories."   
)
DEFINE_bool ( keep_running  ,
false  ,
"Keep running the offline node after all messages from the bag ""have been processed."   
)
DEFINE_double ( skip_seconds  ,
,
"Optional amount of seconds to skip from the beginning ""(i.e. when the earliest bag starts.). "   
)
DEFINE_string ( configuration_directory  ,
""  ,
"First directory in which configuration files are  searched,
""second is always the Cartographer installation to allow""including files from there."   
)
DEFINE_string ( configuration_basenames  ,
""  ,
"Comma-separated list of  basenames,
i.e.not containing any""directory  prefix,
of the configuration files for each trajectory.""The first configuration file will be used for node options.""If less configuration files are specified than  trajectories,
the""first file will be used the remaining trajectories."   
)
DEFINE_string ( bag_filenames  ,
""  ,
"Comma-separated list of bags to process. One bag per trajectory. ""Any combination of simultaneous and sequential bags is supported."   
)
DEFINE_string ( urdf_filenames  ,
""  ,
"Comma-separated list of one or more URDF files that contain ""static links for the sensor configuration(s)."   
)
DEFINE_string ( load_state_filename  ,
""  ,
"If non-  empty,
filename of a.pbstream file to  load,
containing""a saved SLAM state."   
)
DEFINE_string ( save_state_filename  ,
""  ,
"Explicit name of the file to which the serialized state will be ""written before shutdown. If left  empty,
the filename will be""inferred from the first bagfile's name as:""< bag_filenames[0]>.pbstream"   
)


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28