网站后端性能优化措施,网站做网站词怎么推广,泉州seo培训,找人做网站需要先了解哪些要点简单范例
功能描述
使用launch文件#xff0c;统一管理工程#xff0c;实现img转点云#xff0c;发送到img_pt的topic#xff0c;然后用reg_pcl节点进行subscribe#xff0c;进行点云配准处理#xff0c;输出融合后的点云到map_pt的topic。最后由rviz2进行点云展示。
…简单范例
功能描述
使用launch文件统一管理工程实现img转点云发送到img_pt的topic然后用reg_pcl节点进行subscribe进行点云配准处理输出融合后的点云到map_pt的topic。最后由rviz2进行点云展示。
环境准备
ubuntu18.04ros2eloquent此版本需要于Ubuntu对应 Pythonversion3.6需要于eloquent对应PCLEIGENrviz2 具体安装库和依赖不做赘述
代码实现
代码结构
代码结构编译前
pcl_reg
├── CMakeLists.txt
├── config
│ ├── img2pt.yaml
│ └── reg_pcl.yaml
├── include
│ └── pcl_reg
├── launch
│ ├── img2pt.launch.py
│ ├── mapping.launch.py
│ ├── mapping_sub.launch.py
│ ├── reg_pcl.launch.py
│ └── showviz.launch.py
├── package.xml
├── rviz
└── src├── img2pt.cpp├── odom_pre.cpp├── other.txt├── pt_show.cpp└── reg_pcl.cpp代码内容
img转pt的部分图像为rgb三通道的语义图转换为点云点云为pcl::PointXYZRGB的格式XYZ为点云位置RGB对应图像的三通道rgb。其中XY可以通过图像的uv坐标转换得到因为是BEV视角Z坐标统一置零即可。然后由于语义图上的点云数量过多在后续匹配的过程中中会降低效率。可以做一些预处理例如下采样设置权值等。 map2pt.cpp
#include iostream
#include chrono
#include memory
#include rclcpp/rclcpp.hpp
#include sensor_msgs/msg/point_cloud2.hpp
#include pcl_conversions/pcl_conversions.h//for pcl::toROSMsg
#include pcl/io/pcd_io.h
#include pcl/point_types.h
#include pcl/point_cloud.h#include pcl/common/common.h
#include pcl/common/transforms.h
#include pcl/filters/voxel_grid.h
#include pcl/kdtree/kdtree_flann.h#include opencv2/opencv.hpp
#include Eigen/Dense
// typedef pcl::PointXYZRGB pcl::PointXYZRGB;
using namespace std::chrono_literals;class PointCloudPublisher : public rclcpp::Node
{
public:PointCloudPublisher() : Node(point_cloud_publisher){count 1380;param_respond();//参数初始化// timer_param_ this-create_wall_timer(500ms, std::bind(PointCloudPublisher::param_respond, this));// 创建一个Publisher发布PointCloud2消息到名为pt的topicpublisher_ this-create_publishersensor_msgs::msg::PointCloud2(img_pt, 10);// 创建一个定时器每秒钟发布一次PointCloud2消息 std::chrono::seconds(1)timer_ this-create_wall_timer(1s, std::bind(PointCloudPublisher::publishPointCloud, this));}private://使用yaml进行参数配置此处参数只会在初始化时生效一次。如果需要参数随时变化需要做其他处理void param_respond(){//定义可配置参数与yaml文件或launch文件中参数名需要对应需要注意的是参数类型需要匹配否则会报错。并给出参数默认值。this-declare_parameterfloat(voxel_grid_x, 0.05);this-declare_parameterfloat(voxel_grid_y, 0.05);this-declare_parameterfloat(voxel_grid_z, 0.05);//获取参数,并将参数值赋值到对应变量this-get_parameter(voxel_grid_x, voxel_grid_x_);this-get_parameter(voxel_grid_y, voxel_grid_y_);this-get_parameter(voxel_grid_z, voxel_grid_z_);//打印RCLCPP_INFO(this-get_logger(), Hello voxel_grid_x:%f, voxel_grid_y:%f, voxel_grid_z:%f, voxel_grid_x_,voxel_grid_y_,voxel_grid_z_);//将参数统一放到std::vectorrclcpp::Parameter中并set到节点里此时参数文件yaml或launch文件中的数值开始生效。std::vectorrclcpp::Parameter all_new_parameters{rclcpp::Parameter(voxel_grid_x, voxel_grid_x_),rclcpp::Parameter(voxel_grid_y, voxel_grid_y_),rclcpp::Parameter(voxel_grid_z, voxel_grid_z_)};this-set_parameters(all_new_parameters);}void publishPointCloud(){// 创建一个PointCloud对象pcl::PointCloudpcl::PointXYZRGB::Ptr cloud_src(new pcl::PointCloudpcl::PointXYZRGB);std::string path_img /home/apollo/zr/code/data/sim_data/camera1-230829-164731_Lanes/std::to_string(count).jpg;cv::Mat image cv::imread(path_img);// 检查图片是否成功加载if (image.empty()) {std::cout 无法加载图片 std::endl;// return -1;}RCLCPP_INFO(this-get_logger(), Publishing: %d, count);countcount12;pcl::PointCloudpcl::PointXYZRGB::Ptr pointCloud(new pcl::PointCloudpcl::PointXYZRGB);Eigen::Matrix3f matK_ipm_inverse Eigen::Matrix3f::Identity(3, 3);//bias表示车后轴中心在图像像素位置//k_cam表示图像像素和实际尺度m的比例关系float k_cam 0.0325;float x_bias 480*4.0/5.0*k_cam;float y_bias 640/2.0*k_cam;matK_ipm_inverse 0,-k_cam,x_bias,-k_cam,0,y_bias,0,0,1;pointCloud ipmToPointCloud(image,matK_ipm_inverse);// /*// 点云降采样// create new keyFrame, and add pointCloud to global mapbool make_global_map true;pcl::PointCloudpcl::PointXYZRGB::Ptr downsampled_cloud(new pcl::PointCloudpcl::PointXYZRGB);if(make_global_map){// 创建 VoxelGrid 对象pcl::VoxelGridpcl::PointXYZRGB voxel_grid;voxel_grid.setInputCloud(pointCloud);voxel_grid.setLeafSize(voxel_grid_x_, voxel_grid_y_, voxel_grid_z_); // 设置体素大小// 执行下采样voxel_grid.filter(*downsampled_cloud);// *globalFeatureCloudglobalMapDS;RCLCPP_INFO(this-get_logger(), globalFeatureCloud size is: %d, (int)downsampled_cloud-size());}// */// 创建一个PointCloud2消息sensor_msgs::msg::PointCloud2::UniquePtr cloud_msg(new sensor_msgs::msg::PointCloud2);pcl::toROSMsg(*downsampled_cloud, *cloud_msg);// pcl::toROSMsg(*pointCloud, *cloud_msg);cloud_msg-header.frame_id base_link; // 设置坐标系cloud_msg-header.stamp this-now();// 设置PointCloud2消息的时间戳// 发布PointCloud2消息到pt的topicpublisher_-publish(std::move(cloud_msg));}pcl::PointCloudpcl::PointXYZRGB::Ptr ipmToPointCloud(const cv::Mat ipmImage,const Eigen::Matrix3f matK_ipm_inv){pcl::PointCloudpcl::PointXYZRGB::Ptr pointCloudOut(new pcl::PointCloudpcl::PointXYZRGB);for (int y 0; y ipmImage.rows; y) {for (int x 0; x ipmImage.cols; x) {cv::Vec3b pixel ipmImage.atcv::Vec3b(y, x);if (!(pixel[0]0 pixel[1]0 pixel[2]0)) {pcl::PointXYZRGB pclPoint;Eigen::Vector3f uv1(x,y,1);Eigen::Vector3f xyzmatK_ipm_inv*uv1;pclPoint.x xyz(0);pclPoint.y xyz(1);pclPoint.z 0;pclPoint.r pixel[0];pclPoint.g pixel[1];pclPoint.b pixel[2];pointCloudOut-push_back(pclPoint);// if(pixel[0]233, pixel[1]238, pixel[2]12)// {// std::coutu,v:[x,y] x,y:[pclPoint.x,pclPoint.y]std::endl;// }}}}return pointCloudOut;}int count;rclcpp::Publishersensor_msgs::msg::PointCloud2::SharedPtr publisher_;rclcpp::TimerBase::SharedPtr timer_;float voxel_grid_x_;float voxel_grid_y_;float voxel_grid_z_;// rclcpp::TimerBase::SharedPtr timer_param_;
};int main(int argc, char** argv)
{rclcpp::init(argc, argv);auto node std::make_sharedPointCloudPublisher();rclcpp::spin(node);rclcpp::shutdown();/*打开图片: 单独实线功能不使用ros2系统 */// cv::Mat image cv::imread(/home/apollo/zr/code/data/sim_data/camera1-230829-164731_Lanes/1440.jpg);// // 检查图片是否成功加载// if (image.empty()) {// std::cout 无法加载图片 std::endl;// return -1;// }// pcl::PointCloudpcl::PointXYZRGB::Ptr pointCloud(new pcl::PointCloudpcl::PointXYZRGB);// Eigen::Matrix3f matK_ipm Eigen::Matrix3f::Identity(3, 3);// matK_ipm 0,40,1.798070000000000057e00,// -40,0,0,// 0,0,1;// pointCloud ipmToPointCloud(image,matK_ipm);// // 创建窗口并显示图片// cv::namedWindow(Image, cv::WINDOW_NORMAL);// cv::imshow(Image, image);// // 等待按键退出// cv::waitKey(0);return 0;
}reg_pcl.cpp
#include rclcpp/rclcpp.hpp
#include sensor_msgs/msg/point_cloud2.hpp
#include geometry_msgs/msg/transform_stamped.hpp
#include pcl/point_cloud.h
#include pcl/point_types.h
#include pcl_conversions/pcl_conversions.h#include iostream
#include pcl/registration/icp.h
#include pcl/registration/ndt.h
#include pcl/common/common.h
#include pcl/common/transforms.h
#include pcl/filters/voxel_grid.h
#include pcl/kdtree/kdtree_flann.h// 处理点云的函数class PointCloudProcessor : public rclcpp::Node
{
public:PointCloudProcessor() : Node(point_cloud_processor){param_respond();//参数初始化init_flag true;//第一帧标志位第一帧无法进行点云配准count 0;//匹配次数为了保存结果点云计数可选用map_RT Eigen::Matrix4f::Identity();//建图功能累计的位姿矩阵cloud_local_map pcl::PointCloudpcl::PointXYZRGB::Ptr(new pcl::PointCloudpcl::PointXYZRGB);// 创建订阅者订阅 img_pt 话题的点云消息subscription_ this-create_subscriptionsensor_msgs::msg::PointCloud2(img_pt, rclcpp::QoS(10),std::bind(PointCloudProcessor::pointCloudCallback, this, std::placeholders::_1));// 创建发布者发布处理后的点云到 map_pt 话题publisher_ this-create_publishersensor_msgs::msg::PointCloud2(map_pt, rclcpp::QoS(10));}private://使用yaml进行参数配置此处参数只会在初始化时生效一次。如果需要参数随时变化需要做其他处理void param_respond(){//定义可配置参数与yaml文件或launch文件中参数名需要对应需要注意的是参数类型需要匹配否则会报错。并给出参数默认值。this-declare_parameterbool(use_icp, true);this-declare_parameterint(icpMaximumIterations, 1);this-declare_parameterdouble(icpMaxCorrespondenceDistance, 1);this-declare_parameterdouble(icpTransformationEpsilon, 1e-10);this-declare_parameterdouble(icpEuclideanFitnessEpsilon, 0.001);this-declare_parameterdouble(icpFitnessScoreThresh, 0.3);this-declare_parameterdouble(ndtTransformationEpsilon, 1e-10);this-declare_parameterdouble(ndtResolution, 0.1);this-declare_parameterdouble(ndtFitnessScoreThresh, 0.3);//获取参数,并将参数值赋值到对应变量this-get_parameter(use_icp, use_icp_);this-get_parameter(icpMaximumIterations, icpMaximumIterations_);this-get_parameter(icpMaxCorrespondenceDistance, icpMaxCorrespondenceDistance_);this-get_parameter(icpTransformationEpsilon, icpTransformationEpsilon_);this-get_parameter(icpEuclideanFitnessEpsilon, icpEuclideanFitnessEpsilon_);this-get_parameter(icpFitnessScoreThresh, icpFitnessScoreThresh_);this-get_parameter(ndtTransformationEpsilon, ndtTransformationEpsilon_);this-get_parameter(ndtResolution, ndtResolution_);this-get_parameter(ndtFitnessScoreThresh, ndtFitnessScoreThresh_);//调试过程中如果怀疑参数文件有问题可以使用下方直接赋值方法确认其他部分没有问题定位问题到参数文件yaml或launch文件上// icpTransformationEpsilon_ 1e-10;// ndtTransformationEpsilon_ 1e-10;RCLCPP_INFO(this-get_logger(), Hello use_icp:%d, icpMaximumIterations:%d, icpMaxCorrespondenceDistance:%f, use_icp_,icpMaximumIterations_,icpMaxCorrespondenceDistance_);将参数统一放到std::vectorrclcpp::Parameter中并set到节点里此时参数文件yaml或launch文件中的数值开始生效。std::vectorrclcpp::Parameter all_new_parameters{rclcpp::Parameter(use_icp, use_icp_),rclcpp::Parameter(icpMaximumIterations, icpMaximumIterations_),rclcpp::Parameter(icpMaxCorrespondenceDistance, icpMaxCorrespondenceDistance_),rclcpp::Parameter(icpTransformationEpsilon, icpTransformationEpsilon_),rclcpp::Parameter(icpEuclideanFitnessEpsilon, icpEuclideanFitnessEpsilon_),rclcpp::Parameter(icpFitnessScoreThresh, icpFitnessScoreThresh_),rclcpp::Parameter(ndtTransformationEpsilon, ndtTransformationEpsilon_),rclcpp::Parameter(ndtResolution, ndtResolution_),rclcpp::Parameter(ndtFitnessScoreThresh, ndtFitnessScoreThresh_)};this-set_parameters(all_new_parameters);}void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr input_msg){std::coutrcv pt msgstd::endl;// 将接收到的点云消息转换为 pcl::PointCloudpcl::PointXYZRGB 类型pcl::PointCloudpcl::PointXYZRGB::Ptr cameraCloudIn(new pcl::PointCloudpcl::PointXYZRGB);pcl::fromROSMsg(*input_msg, *cameraCloudIn);if(init_flag){//第一帧不做匹配仅保存cloud_src cameraCloudIn;cloud_local_map cameraCloudIn;init_flag false;return ; }else{cloud_tgt cloud_src;cloud_src cameraCloudIn;//计时开始rclcpp::Clock steady_clock_{RCL_STEADY_TIME};auto start_time steady_clock_.now();// 点云配准mapping_local(cloud_src,cloud_tgt);// 计时结束并计算costauto cycle_duration steady_clock_.now() - start_time;std::couticp cost time:cycle_duration.seconds() sstd::endl;RCLCPP_INFO(get_logger(), Cost %.4f s, cycle_duration.seconds());}// 将处理后的点云转换为 sensor_msgs::msg::PointCloud2 类型sensor_msgs::msg::PointCloud2::UniquePtr result_msg(new sensor_msgs::msg::PointCloud2);pcl::toROSMsg(*cloud_local_map, *result_msg);// pcl::toROSMsg(*cloud_src, *result_msg);result_msg-header.frame_id base_link2; // 设置坐标系result_msg-header.stamp this-now();// 设置PointCloud2消息的时间戳// 发布处理后的点云到 map_pt 话题publisher_-publish(std::move(result_msg));}void mapping_local(const pcl::PointCloudpcl::PointXYZRGB::Ptr src_cloud,const pcl::PointCloudpcl::PointXYZRGB::Ptr tgt_cloud){Eigen::Matrix4f transWorldCurrent Eigen::Matrix4f::Identity();transWorldCurrent(0,3)1;// printMat4(transWorldCurrent);pcl::PointCloudpcl::PointXYZRGB::Ptr currentFeatureCloudInWorld(new pcl::PointCloudpcl::PointXYZRGB());if(use_icp_){static pcl::IterativeClosestPointpcl::PointXYZRGB, pcl::PointXYZRGB icp;icp.setMaxCorrespondenceDistance(icpMaxCorrespondenceDistance_); icp.setMaximumIterations(icpMaximumIterations_);icp.setTransformationEpsilon(icpTransformationEpsilon_);icp.setEuclideanFitnessEpsilon(icpEuclideanFitnessEpsilon_);icp.setInputSource(src_cloud);icp.setInputTarget(tgt_cloud);pcl::PointCloudpcl::PointXYZRGB::Ptr transCurrentCloudInWorld(new pcl::PointCloudpcl::PointXYZRGB());icp.align(*transCurrentCloudInWorld,transWorldCurrent.matrix());//迭代效果不理想原因尚未定位到if (icp.hasConverged() false || icp.getFitnessScore() icpFitnessScoreThresh_) {std::cout ICP locolization failed the score is icp.getFitnessScore() std::endl;return ;} else {transWorldCurrent icp.getFinalTransformation();printMat4(transWorldCurrent);}}else{pcl::NormalDistributionsTransformpcl::PointXYZRGB, pcl::PointXYZRGB ndt;ndt.setTransformationEpsilon(ndtTransformationEpsilon_);ndt.setResolution(ndtResolution_);ndt.setInputSource(src_cloud);ndt.setInputTarget(tgt_cloud);pcl::PointCloudpcl::PointXYZRGB::Ptr transCurrentCloudInWorld(new pcl::PointCloudpcl::PointXYZRGB());ndt.align(*transCurrentCloudInWorld, transWorldCurrent.matrix());//会直接退出程序原因尚未定位到if (ndt.hasConverged() false || ndt.getFitnessScore() ndtFitnessScoreThresh_) {std::cout ndt locolization failed the score is ndt.getFitnessScore() std::endl;return ;} else{ transWorldCurrent ndt.getFinalTransformation();printMat4(transWorldCurrent);}} map_RT map_RT*transWorldCurrent;pcl::transformPointCloud (*src_cloud, *currentFeatureCloudInWorld, map_RT);/*// 保存pcd文件方便pcl_viewer pcdfile.pcdcount;std::string filename1 /home/apollo/zr/code/resultpcd/src_tgtstd::to_string(count).pcd;pcl::PointCloudpcl::PointXYZRGB::Ptr show_cloud1(new pcl::PointCloudpcl::PointXYZRGB);*show_cloud1 *show_cloud1*src_cloud;*show_cloud1 *show_cloud1*tgt_cloud;pcl::io::savePCDFileBinary(filename1, *show_cloud1);std::string filename2 /home/apollo/zr/code/resultpcd/tgt_transstd::to_string(count).pcd;pcl::PointCloudpcl::PointXYZRGB::Ptr show_cloud2(new pcl::PointCloudpcl::PointXYZRGB);*show_cloud2 *show_cloud2*tgt_cloud;*show_cloud2 *show_cloud2*currentFeatureCloudInWorld;pcl::io::savePCDFileBinary(filename2, *show_cloud2);*/// 创建新的帧并将src点云后续需要换成匹配点云点对添加进map点云*cloud_local_map *cloud_local_map*currentFeatureCloudInWorld;RCLCPP_INFO(this-get_logger(), cloud_local_map size is: %d, (int)cloud_local_map-size());//}rclcpp::Subscriptionsensor_msgs::msg::PointCloud2::SharedPtr subscription_;rclcpp::Subscriptiongeometry_msgs::msg::TransformStamped::SharedPtr subscription_odom_;rclcpp::Publishersensor_msgs::msg::PointCloud2::SharedPtr publisher_;Eigen::Matrix4f map_RT;pcl::PointCloudpcl::PointXYZRGB::Ptr cloud_local_map;pcl::PointCloudpcl::PointXYZRGB::Ptr cloud_src; //不需要初始化后面会赋值pcl::PointCloudpcl::PointXYZRGB::Ptr cloud_tgt;//不需要初始化后面会赋值bool init_flag;int count;bool use_icp_ true;double icpMaxCorrespondenceDistance_1;//100int icpMaximumIterations_1;//100double icpTransformationEpsilon_1e-10;double icpEuclideanFitnessEpsilon_0.001;double icpFitnessScoreThresh_0.3;//0.3double ndtTransformationEpsilon_1e-10;double ndtResolution_0.1;double ndtFitnessScoreThresh_0.3;void printMat4(Eigen::Matrix4f mat){std::coutmatrix is :std::endl;for(int i0;imat.rows();i){for(int j0;jmat.cols();j){std::coutmat(i,j) , ;}std::coutstd::endl;}}
};int main(int argc, char** argv)
{rclcpp::init(argc, argv);rclcpp::spin(std::make_sharedPointCloudProcessor());rclcpp::shutdown();return 0;
}对CMakeLists.txt进行适当修改
cmake_minimum_required(VERSION 3.5)
project(pcl_reg)# Default to C99
if(NOT CMAKE_C_STANDARD)set(CMAKE_C_STANDARD 99)
endif()# Default to C14
if(NOT CMAKE_CXX_STANDARD)set(CMAKE_CXX_STANDARD 14)
endif()if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES Clang)add_compile_options(-Wall -Wextra -Wpedantic)
endif()# 寻找依赖库标准库
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)# 寻找依赖库外部库
find_package(Eigen3 REQUIRED)
# 针对PCL库版本不适配会出现warning做的补丁其实没有解决问题
if(NOT DEFINED CMAKE_SUPPRESS_DEVELOPER_WARNINGS)set(CMAKE_SUPPRESS_DEVELOPER_WARNINGS 1 CACHE INTERNAL No dev warnings)
endif()
find_package(PCL REQUIRED)
find_package(rviz2 REQUIRED)
find_package(OpenCV 3.2.0 REQUIRED)# 添加包含路径
include_directories(/usr/include${EIGEN3_INCLUDE_DIRS}${PCL_INCLUDE_DIRS}${RVIZ2_INCLUDE_DIRS}/usr/include/OGRE${OpenCV_INCLUDE_DIRS}
)# 添加可执行文件
add_executable(reg_pcl src/reg_pcl.cpp)
ament_target_dependencies(reg_pcl rclcpp sensor_msgs)
target_link_libraries(reg_pcl${PCL_LIBRARIES}# ${OpenCV_LIBS}
)
add_executable(img2pt src/img2pt.cpp)
ament_target_dependencies(img2pt rclcpp sensor_msgs)
target_link_libraries(img2pt${PCL_LIBRARIES}${OpenCV_LIBS}
)add_executable(odom_pre src/odom_pre.cpp)
ament_target_dependencies(odom_pre rclcpp sensor_msgs)
# target_link_libraries(odom_pre
# ${PCL_LIBRARIES}
# ${OpenCV_LIBS}
# )# add_executable(pt_show src/pt_show.cpp)
# ament_target_dependencies(pt_show rclcpp sensor_msgs)
# target_link_libraries(pt_show
# ${PCL_LIBRARIES}
# ${RVIZ2_LIBRARIES}
# # ${OpenCV_LIBS}
# )
##安装可执行文件
install(TARGETS reg_pcl img2ptodom_pre# pt_show# EXPORT export_${PROJECT_NAME}DESTINATION lib/${PROJECT_NAME})##安装launch文件,无论该功能包的launch目录下有多少个launch文件launch相关配置只需要设置一次即可。ros2 launch 包名 launch文件名无需带上launch文件夹地址
install(DIRECTORY launchconfigDESTINATION share/${PROJECT_NAME}/
)if(BUILD_TESTING)find_package(ament_lint_auto REQUIRED)ament_lint_auto_find_test_dependencies()
endif()ament_package()
对package.xml进行适当修改
?xml version1.0?
?xml-model hrefhttp://download.ros.org/schema/package_format3.xsd schematypenshttp://www.w3.org/2001/XMLSchema?
package format3namepcl_reg/nameversion0.0.0/versiondescriptionTODO: Package description/descriptionmaintainer emailapollotodo.todoapollo/maintainerlicenseTODO: License declaration/licensedependrclcpp/dependdependsensor_msgs/dependdependEIGEN3/dependdependPCL/dependdependOpenCV/depend!-- ros2 launch 使得launch file可以被识别 --exec_dependros2launch/exec_depend buildtool_dependament_cmake/buildtool_dependtest_dependament_lint_auto/test_dependtest_dependament_lint_common/test_dependexportbuild_typeament_cmake/build_type/export
/package
launch文件 img2pt.launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
import os
from ament_index_python.packages import get_package_share_directorydef generate_launch_description():config os.path.join(get_package_share_directory(pcl_reg),config,img2pt.yaml)return LaunchDescription([Node(packagepcl_reg,node_executableimg2pt,namepoint_cloud_publisher,outputscreen,emulate_ttyTrue,parameters[config],# parameters[# {voxel_grid_x:0.08},# {voxel_grid_y:0.12},# {voxel_grid_z:0.66}# ]),])reg_pcl.launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
import os
from ament_index_python.packages import get_package_share_directorydef generate_launch_description():config os.path.join(get_package_share_directory(pcl_reg),config,reg_pcl.yaml)return LaunchDescription([Node(packagepcl_reg,node_executablereg_pcl,namepoint_cloud_processor,outputscreen,emulate_ttyTrue,parameters[config],# parameters[# {voxel_grid_x:0.08},# {voxel_grid_y:0.12},# {voxel_grid_z:0.66}# ]),])mapping.launch.py
from launch import LaunchDescription
from launch_ros.actions import Nodedef generate_launch_description():return LaunchDescription([Node(packagepcl_reg,node_executableimg2pt,namepoint_cloud_publisher,outputscreen,emulate_ttyTrue,),Node(packagepcl_reg,node_executablereg_pcl,namepoint_cloud_processor,outputscreen,emulate_ttyTrue,),##ExecuteProcess是针对有终端输入的情况# ExecuteProcess()])# def generate_launch_description():
# ld LaunchDescription()# node1 Node(
# packagepcl_reg,
# eloquent版本不能用executable要使用node_executable
# node_executableimg2pt,
# # namepoint_cloud_publisher,
# # outputscreen
# )# ld.add_action(node1)# return ldshowviz.launch.py
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Nodedef generate_launch_description():# rviz_config os.path.join(# get_package_share_directory(pcl_reg),# rviz2,# map_pt_conf.rviz# )rviz_config os.path.join(/home,apollo,.rviz2,map_pt_conf.rviz)return LaunchDescription([Node(packagerviz2,node_executablerviz2,# namerviz2, arguments[-d, rviz_config])])mapping_sub.launch.py
import osfrom ament_index_python.packages import get_package_share_directoryfrom launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSourcedef generate_launch_description():img2pt IncludeLaunchDescription(PythonLaunchDescriptionSource([os.path.join(get_package_share_directory(pcl_reg), launch),/img2pt.launch.py]))reg_pcl IncludeLaunchDescription(PythonLaunchDescriptionSource([os.path.join(get_package_share_directory(pcl_reg), launch),/reg_pcl.launch.py]))rviz_node IncludeLaunchDescription(PythonLaunchDescriptionSource([os.path.join(get_package_share_directory(pcl_reg), launch),/showviz.launch.py]))return LaunchDescription([img2pt,reg_pcl,# rviz_node])img2pt.yaml
point_cloud_publisher: #节点名、不是excutable文件名ros__parameters: #固定形式use_sim_time: false #是否使用仿真时间一般为falsevoxel_grid_x: 0.05voxel_grid_y: 0.05voxel_grid_z: 0.85reg_pcl.yaml
point_cloud_processor:ros__parameters:use_sim_time: falseuse_icp_: trueicpMaximumIterations: 1 #100 int型请务必写整数icpMaxCorrespondenceDistance: 1.0005 #double类型不要直接写1要写带小数点的icpTransformationEpsilon: 1e-10 #支持科学计数法icpEuclideanFitnessEpsilon: 0.001icpFitnessScoreThresh: 0.3ndtTransformationEpsilon: 1e-10ndtResolution: 0.1ndtFitnessScoreThresh: 0.3使用rviz2订阅topic查看点云
编写代码订阅topic查看点云
报错经验总结
ros1系统性卡死
rosnode list #查看节点 rosnode kill #杀死节点 rosnode cleanup #清除无法访问节点的注册信息:杀死kill杀不死的节点
空间或内存或log空间不够时也是gazebo相关报错使用gazebo时需要内存和空间
conda clean --all #清除conda缓存 top #或者top查看进程中谁占用内存较大并kill掉 rm -rf ~/.ros #清除ros缓存/也可以避免~/.ros/log权限问题
ros1和ros2切换
source /opt/ros/eloquent/setup.bash #ROS2对应ubuntu18版本为eloquent source /opt/ros/melodic/setup.bash #ROS1对应ubuntu18版本为melodic 一个终端内尽量不要来回切换版本如果出现ROS_DISTRO相关提示请关闭终端重新打开