parent
3592b13871
commit
e576d72dfc
|
@ -135,8 +135,8 @@ Visualization Manager:
|
|||
Enabled: true
|
||||
Map frame: map
|
||||
Name: Submaps
|
||||
Submap query service: /cartographer/submap_query
|
||||
Topic: /cartographer/submap_list
|
||||
Submap query service: /submap_query
|
||||
Topic: /submap_list
|
||||
Tracking frame: base_link
|
||||
Unreliable: false
|
||||
Value: true
|
||||
|
|
|
@ -197,8 +197,8 @@ Visualization Manager:
|
|||
Enabled: true
|
||||
Map frame: map
|
||||
Name: Submaps
|
||||
Submap query service: /cartographer/submap_query
|
||||
Topic: /cartographer/submap_list
|
||||
Submap query service: /submap_query
|
||||
Topic: /submap_list
|
||||
Tracking frame: base_link
|
||||
Unreliable: false
|
||||
Value: true
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
<node name="robot_state_publisher" pkg="robot_state_publisher"
|
||||
type="robot_state_publisher" />
|
||||
|
||||
<node name="cartographer" pkg="cartographer_ros"
|
||||
<node name="cartographer_node" pkg="cartographer_ros"
|
||||
type="cartographer_node" args="
|
||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||
-configuration_basename backpack_2d.lua"
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
<node name="robot_state_publisher" pkg="robot_state_publisher"
|
||||
type="robot_state_publisher" />
|
||||
|
||||
<node name="cartographer" pkg="cartographer_ros"
|
||||
<node name="cartographer_node" pkg="cartographer_ros"
|
||||
type="cartographer_node" args="
|
||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||
-configuration_basename backpack_3d.lua"
|
||||
|
|
|
@ -92,13 +92,13 @@ constexpr int kSubscriberQueueSize = 150;
|
|||
constexpr double kSensorDataRatesLoggingPeriodSeconds = 15.;
|
||||
|
||||
// Unique default topic names. Expected to be remapped as needed.
|
||||
constexpr char kLaserScanTopic[] = "/scan";
|
||||
constexpr char kMultiEchoLaserScanTopic[] = "/echoes";
|
||||
constexpr char kPointCloud2Topic[] = "/points2";
|
||||
constexpr char kImuTopic[] = "/imu";
|
||||
constexpr char kOdometryTopic[] = "/odom";
|
||||
constexpr char kOccupancyGridTopic[] = "/map";
|
||||
constexpr char kScanMatchedPointCloudTopic[] = "/scan_matched_points2";
|
||||
constexpr char kLaserScanTopic[] = "scan";
|
||||
constexpr char kMultiEchoLaserScanTopic[] = "echoes";
|
||||
constexpr char kPointCloud2Topic[] = "points2";
|
||||
constexpr char kImuTopic[] = "imu";
|
||||
constexpr char kOdometryTopic[] = "odom";
|
||||
constexpr char kOccupancyGridTopic[] = "map";
|
||||
constexpr char kScanMatchedPointCloudTopic[] = "scan_matched_points2";
|
||||
|
||||
struct NodeOptions {
|
||||
carto::mapping::proto::MapBuilderOptions map_builder_options;
|
||||
|
@ -262,7 +262,6 @@ Node::Node(const NodeOptions& options)
|
|||
: options_(options),
|
||||
map_builder_(options.map_builder_options, &constant_data_),
|
||||
sensor_data_producer_(kTrajectoryBuilderId, &sensor_collator_),
|
||||
node_handle_("~"),
|
||||
tf_buffer_(::ros::Duration(1000)),
|
||||
tf_(tf_buffer_) {}
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@ constexpr char kDefaultTrackingFrame[] = "base_link";
|
|||
SubmapsDisplay::SubmapsDisplay() : tf_listener_(tf_buffer_) {
|
||||
submap_query_service_property_ = new ::rviz::StringProperty(
|
||||
"Submap query service",
|
||||
QString("/cartographer/") + kSubmapQueryServiceName,
|
||||
QString("/") + kSubmapQueryServiceName,
|
||||
"Submap query service to connect to.", this, SLOT(Reset()));
|
||||
map_frame_property_ = new ::rviz::StringProperty(
|
||||
"Map frame", kDefaultMapFrame, "Map frame, used for fading out submaps.",
|
||||
|
|
Loading…
Reference in New Issue