官网链接:Running Cartographer ROS on a demo bag — Cartographer ROS documentation
1.运行landmark dmeo
1.1 下载数据包
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/mir/landmarks_demo_uncalibrated.bag
1.2 在src下 下载cartographer_mir
cd car2_ws/src
git clone https://github.com/googlecartographer/cartographer_mir.git
1.3 重新编译car2_ws
catkin_make_isolated --install --use-ninja
source install_isolated/setup.bash
1.4 运行demo:
roslaunch cartographer_mir offline_mir_100_rviz.launch bag_filenames:=${HOME}/Downloads/landmarks_demo_uncalibrated.bag
1.5 运行结果:
2. 建立发布静态landmark节点
参考链接:cartographer使用landmark_花生啤酒八宝粥的博客-CSDN博客
2.1 创建工作空间和节点
参考链接:如何在ROS中使用VScode创建功能包并编写cpp文件_ros创建.cpp文件命令_舟同学的博客的博客-CSDN博客
2.1.1.创建工作空间
mkdir -p pl/src
2.1.2.编译
catkin_make
2.1.3.创建功能包
cd src
catkin_create_pkg pub_landmark roscpp rospy std_msgs
2.2 配置头文件
将~/car2_ws/install_isolated/include/cartographer_ros_msgs下的两个配置文件放入~/pl/src/pub_landmark/include/pub_landmark下
将头文件存在路径加入c_cpp_properties.json文件
2.3 创建自定义消息类型
1.定义msg文件
功能包下新建 msg 目录,添加文件 LandmarkEntry.msg、LandmarkList.h
2.编辑配置文件
package.xml中添加编译依赖与执行依赖
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
2.4 创建cpp文件
文件内容:
#include "ros/ros.h"
#include "pub_landmark/LandmarkList.h"
#include "pub_landmark/LandmarkEntry.h"
#include "geometry_msgs/Pose.h"
#include "std_msgs/String.h"
#include "std_msgs/Header.h"
int main(int argc, char *argv[])
{
ros::init(argc, argv, "pub_landmark");
ros::NodeHandle nh;
ros::NodeHandle n("~");
ros::Publisher landmark_pub = n.advertise<cartographer_ros_msgs::LandmarkList>("landmark", 10);
cartographer_ros_msgs::LandmarkList landmark_0;
ros::Rate loop_rate(10);
int count=0;
while (ros::ok())
{
landmark_0.header.stamp = ros::Time::now();
landmark_0.header.frame_id = "base_link";
landmark_0.landmarks.resize(10);
for(int t=0;t<10;t++)
{
std::stringstream ss;
ss << t;//"landmark_" ;//<< count/ << "_" t;
landmark_0.landmarks[t].id = ss.str();
landmark_0.landmarks[t].tracking_from_landmark_transform.position.x = 1.0*t;
landmark_0.landmarks[t].tracking_from_landmark_transform.position.y = 2.0*t;
landmark_0.landmarks[t].tracking_from_landmark_transform.position.z = 3.0*t;
landmark_0.landmarks[t].tracking_from_landmark_transform.orientation.w = 1.0*t;
landmark_0.landmarks[t].tracking_from_landmark_transform.orientation.x = 0.0*t;
landmark_0.landmarks[t].tracking_from_landmark_transform.orientation.y = 0.0*t;
landmark_0.landmarks[t].tracking_from_landmark_transform.orientation.z = 0.0*t;
landmark_0.landmarks[t].translation_weight = 1.0*t;
landmark_0.landmarks[t].rotation_weight = 2.0*t;
}
landmark_pub.publish(landmark_0);
ROS_INFO("%d", count);
loop_rate.sleep();
count++;
}
return 0;
}
2.5 CMakeList.txt文件配置
如下:
cmake_minimum_required(VERSION 3.0.2)
project(pub_landmark)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
sensor_msgs
)
add_message_files(
FILES
LandmarkEntry.msg
LandmarkList.msg
)
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
geometry_msgs
)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES pub_landmark
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
# DEPENDS system_lib
)
include_directories(
include
${catkin_INCLUDE_DIRS}
)
add_executable(pub src/pub_landmark.cpp)
add_dependencies(pub ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(pub
${catkin_LIBRARIES}
)
2.6 测试发布【与imu、雷达一起发布测试】
节点图:
效果图: