紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
只用激光雷达建图
-
最近搞了一个激光雷达,想尝试一下只用激光雷达建图,使用
fishbot
的foxy版本,参考Cartographer手持雷达SLAM建图配置指南修改了fishbot_laser_2d.lua
配置文件。主要修改了tracking_frame = "laser_link", published_frame = "laser_link",
其他内容并没有改变。运行
cartographer_pure_laser.launch.py
,出现以下错误[cartographer_node-1] F1124 16:19:54.841533 47738 lua_parameter_dictionary.cc:410] Check failed: 1 == reference_counts_.count(key) (1 vs. 0) Key 'use_pose_extrapolator' was used the wrong number of times. [cartographer_node-1] [FATAL] [1669277994.841823999] [cartographer_ros]: F1124 16:19:54.000000 47738 lua_parameter_dictionary.cc:410] Check failed: 1 == reference_counts_.count(key) (1 vs. 0) Key 'use_pose_extrapolator' was used the wrong number of times. [rviz2-3] [INFO] [1669277995.278164232] [rviz2]: Stereo is NOT SUPPORTED [rviz2-3] [INFO] [1669277995.278315296] [rviz2]: OpenGl version: 4.6 (GLSL 4.6) [rviz2-3] [INFO] [1669277995.317479061] [rviz2]: Stereo is NOT SUPPORTED [cartographer_node-1] *** Check failure stack trace: *** [cartographer_node-1] @ 0x7f94f09811c3 google::LogMessage::Fail() [cartographer_node-1] @ 0x7f94f098625b google::LogMessage::SendToLog() [cartographer_node-1] @ 0x7f94f0980ebf google::LogMessage::Flush() [occupancy_grid_node-2] [WARN] [1669277995.846680169] [occupancy_grid_node]: submap_slices and last_frame_id is empty [cartographer_node-1] @ 0x7f94f09816ef google::LogMessageFatal::~LogMessageFatal() [cartographer_node-1] @ 0x557f8ac7f354 cartographer::common::LuaParameterDictionary::CheckAllKeysWereUsedExactlyOnceAndReset() [cartographer_node-1] @ 0x557f8ac7f5e5 cartographer::common::LuaParameterDictionary::~LuaParameterDictionary() [cartographer_node-1] @ 0x557f8ac62bff cartographer_ros::LoadOptions() [cartographer_node-1] @ 0x557f8abd8244 main [cartographer_node-1] @ 0x7f94efedd083 __libc_start_main [cartographer_node-1] @ 0x557f8abdab6e _start [ERROR] [cartographer_node-1]: process has died [pid 47738, exit code -6, cmd '/home/lorry/Code/Ros2/workspace/LearningProject/fishbot/install/cartographer_ros/lib/cartographer_ros/cartographer_node -configuration_directory /home/lorry/Code/Ros2/workspace/LearningProject/fishbot/install/fishbot_cartographer/share/fishbot_cartographer/config -configuration_basename revo_lds.lua --ros-args -r __node:=cartographer_node --params-file /tmp/launch_params_fze1abjy']. [occupancy_grid_node-2] [WARN] [1669277996.846672111] [occupancy_grid_node]: submap_slices and last_frame_id is empty [occupancy_grid_node-2] [WARN] [1669277997.846730475] [occupancy_grid_node]: submap_slices and last_frame_id is empty [occupancy_grid_node-2] [WARN] [1669277998.846736523] [occupancy_grid_node]: submap_slices and last_frame_id is empty
rviz界面什么也没显示
-
-
-
@Lorry map->laser的信息是carto发布的,carto根据雷达信息计算出来雷达在地图中的姿态,所以前置是不需要发布这个关系的
-
@小鱼 我还有个疑惑,配置文件中指定了雷达的frameID,但是并没有指定雷达的话题名称,这样的话建图节点怎么去使用雷达数据?
-
@Lorry 订阅的默认话题'scan'具体可以见cartograpgher_ros代码
cartographer_ros/include/cartographer_ros/node_constants.h
文件26行,如果想改可以用ros2的话题重映射即可/* * 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. */ #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_CONSTANTS_H #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_CONSTANTS_H #include <string> #include <vector> namespace cartographer_ros { // 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 kNavSatFixTopic[] = "fix"; constexpr char kLandmarkTopic[] = "landmark"; constexpr char kFinishTrajectoryServiceName[] = "finish_trajectory"; constexpr char kOccupancyGridTopic[] = "map"; constexpr char kScanMatchedPointCloudTopic[] = "scan_matched_points2"; constexpr char kSubmapListTopic[] = "submap_list"; constexpr char kTrackedPoseTopic[] = "tracked_pose"; constexpr char kSubmapQueryServiceName[] = "submap_query"; constexpr char kTrajectoryQueryServiceName[] = "trajectory_query"; constexpr char kStartTrajectoryServiceName[] = "start_trajectory"; constexpr char kWriteStateServiceName[] = "write_state"; constexpr char kGetTrajectoryStatesServiceName[] = "get_trajectory_states"; constexpr char kReadMetricsServiceName[] = "read_metrics"; constexpr char kTrajectoryNodeListTopic[] = "trajectory_node_list"; constexpr char kLandmarkPosesListTopic[] = "landmark_poses_list"; constexpr char kConstraintListTopic[] = "constraint_list"; constexpr double kConstraintPublishPeriodSec = 0.5; constexpr double kTopicMismatchCheckDelaySec = 3.0; constexpr int kInfiniteSubscriberQueueSize = 0; constexpr int kLatestOnlyPublisherQueueSize = 1; // For multiple topics adds numbers to the topic name and returns the list. std::vector<std::string> ComputeRepeatedTopicNames(const std::string& topic, int num_topics); } // namespace cartographer_ros #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_CONSTANTS_H
-
@小鱼 对nav2太不了解了。
现在定位到的问题是carto并没有发布map->laser_frame的tf变换关系。具体报错是:[occupancy_grid_node-3] [WARN] [1669281762.444819311] [occupancy_grid_node]: submap_slices and last_frame_id is empty [rviz2-4] [INFO] [1669281762.513897803] [rviz2]: Message Filter dropping message: frame 'laser_frame' at time 1669281762.011 for reason 'Unknown'
我再查查解决办法,不行的话就先停下来把nav2看完
-
@Lorry 注意下use_sim_time,仿真时间和实际时间的区别
-
@小鱼 仿真时间设置的是false,应该不会是它引起的