创业做网站需要哪些必备条件/优化大师app
文章目录
- 0 引言
- 1 D435i相机配置
- 2 新增发布双目位姿功能
- 2.1 新增d435i_stereo.cc代码
- 2.2 修改CMakeLists.txt
- 2.3 新增配置文件D435i.yaml
- 3 编译运行和结果
- 3.1 编译运行
- 3.2 结果
- 3.3 可能出现的问题
0 引言
ORB-SLAM2学习笔记1已成功编译安装ROS
版本ORB-SLAM2
到本地,以及ORB-SLAM2学习笔记5成功用EuRoc、TUM、KITTI
开源数据来运行ROS
版ORB-SLAM2
,并生成轨迹。但实际ROS
视觉SLAM
工程落地时,一般搭配传感器实时发出位姿pose
的rostopic
,本篇就以D435i
相机的双目IR
相机作为输入,运行ROS
版ORB-SLAM2
,最后发出pose
的rostopic
。
👉 ORB-SLAM2 github: https://github.com/raulmur/ORB_SLAM2
本文系统环境:
- Ubuntu18.04
- ROS-melodic
- ROS版ORB-SLAM2
- D435i相机和驱动
1 D435i相机配置
默认已在Ubuntu18.04
系统上安装ROS
版的D435i
相机驱动,比如本文驱动安装目录~/catkin_rs/src/realsense-ros
安装后,默认是不开双目IR
相机,需要自行修改配置:
# 激活环境
source /catkin_rs/devel/setup.bash
# roscd 进入到配置文件目录下
roscd realsense2_camera/launch/
# 打开 rs_camera.launch 配置文件进行修改
vim rs_camera.launch
打开后,主要是如下的字段需要修改成 true
,这样就能打开双目IR
相机,分辨率也可自行修改。
<arg name="infra_width" default="848"/><arg name="infra_height" default="480"/><arg name="enable_infra" default="true"/><arg name="enable_infra1" default="true"/><arg name="enable_infra2" default="true"/>
...
2 新增发布双目位姿功能
2.1 新增d435i_stereo.cc代码
在ORB_SLAM2/Examples/ROS/ORB_SLAM2/src/
目录下新增d435i_stereo.cc
代码文件,如下代码片段来增加:
#include<iostream>
#include<algorithm>
#include<fstream>
#include<chrono>#include<tf/transform_broadcaster.h>
#include "../../../include/Converter.h"
#include <nav_msgs/Path.h>#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>#include<opencv2/core/core.hpp>#include"../../../include/System.h"using namespace std;class ImageGrabber
{
public:ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}void GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight);ORB_SLAM2::System* mpSLAM;bool do_rectify;cv::Mat M1l,M2l,M1r,M2r;
};ros::Publisher pose_pub;
nav_msgs::Path stereo_path;
ros::Publisher stereo_path_pub;int main(int argc, char **argv)
{ros::init(argc, argv, "RGBD");ros::start();if(argc != 4){cerr << endl << "Usage: rosrun ORB_SLAM2 Stereo path_to_vocabulary path_to_settings do_rectify" << endl;ros::shutdown();return 1;} // Create SLAM system. It initializes all system threads and gets ready to process frames.ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true);ImageGrabber igb(&SLAM);stringstream ss(argv[3]);ss >> boolalpha >> igb.do_rectify;if(igb.do_rectify){ // Load settings related to stereo calibrationcv::FileStorage fsSettings(argv[2], cv::FileStorage::READ);if(!fsSettings.isOpened()){cerr << "ERROR: Wrong path to settings" << endl;return -1;}cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r;fsSettings["LEFT.K"] >> K_l;fsSettings["RIGHT.K"] >> K_r;fsSettings["LEFT.P"] >> P_l;fsSettings["RIGHT.P"] >> P_r;fsSettings["LEFT.R"] >> R_l;fsSettings["RIGHT.R"] >> R_r;fsSettings["LEFT.D"] >> D_l;fsSettings["RIGHT.D"] >> D_r;int rows_l = fsSettings["LEFT.height"];int cols_l = fsSettings["LEFT.width"];int rows_r = fsSettings["RIGHT.height"];int cols_r = fsSettings["RIGHT.width"];if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() ||rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0){cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl;return -1;}cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l);cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r);}ros::NodeHandle nh;//message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/left/image_raw", 1);//message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "camera/right/image_raw", 1);message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/infra1/image_rect_raw", 1);message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "/camera/infra2/image_rect_raw", 1);typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol;message_filters::Synchronizer<sync_pol> sync(sync_pol(10), left_sub,right_sub);sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2));pose_pub = nh.advertise<geometry_msgs::PoseStamped>("ORB_SLAM/pose", 5);stereo_path_pub = nh.advertise<nav_msgs::Path>("ORB_SLAM/path",10);ros::spin();// Stop all threadsSLAM.Shutdown();// Save camera trajectorySLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory_TUM_Format.txt");SLAM.SaveTrajectoryTUM("FrameTrajectory_TUM_Format.txt");SLAM.SaveTrajectoryKITTI("FrameTrajectory_KITTI_Format.txt");ros::shutdown();return 0;
}void ImageGrabber::GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight)
{// Copy the ros image message to cv::Mat.cv_bridge::CvImageConstPtr cv_ptrLeft;try{cv_ptrLeft = cv_bridge::toCvShare(msgLeft);}catch (cv_bridge::Exception& e){ROS_ERROR("cv_bridge exception: %s", e.what());return;}cv_bridge::CvImageConstPtr cv_ptrRight;try{cv_ptrRight = cv_bridge::toCvShare(msgRight);}catch (cv_bridge::Exception& e){ROS_ERROR("cv_bridge exception: %s", e.what());return;}if(do_rectify){cv::Mat imLeft, imRight;cv::remap(cv_ptrLeft->image,imLeft,M1l,M2l,cv::INTER_LINEAR);cv::remap(cv_ptrRight->image,imRight,M1r,M2r,cv::INTER_LINEAR);mpSLAM->TrackStereo(imLeft,imRight,cv_ptrLeft->header.stamp.toSec()).clone();}else{cv::Mat Tcw;Tcw = mpSLAM->TrackStereo(cv_ptrLeft->image,cv_ptrRight->image,cv_ptrLeft->header.stamp.toSec());geometry_msgs::PoseStamped pose;pose.header.stamp = ros::Time::now();pose.header.frame_id ="path";cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); // Rotation informationcv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); // translation informationvector<float> q = ORB_SLAM2::Converter::toQuaternion(Rwc);tf::Transform new_transform;new_transform.setOrigin(tf::Vector3(twc.at<float>(0, 0), twc.at<float>(0, 1), twc.at<float>(0, 2)));tf::Quaternion quaternion(q[0], q[1], q[2], q[3]);new_transform.setRotation(quaternion);tf::poseTFToMsg(new_transform, pose.pose);pose_pub.publish(pose);stereo_path.header.frame_id="path";stereo_path.header.stamp=ros::Time::now();stereo_path.poses.push_back(pose);stereo_path_pub.publish(stereo_path);}
}
上述代码已经写入了D435i
相机双目IR
相机发出的topic
,分别是左目/camera/infra1/image_rect_raw
,右目/camera/infra2/image_rect_raw
;发布的位姿pose
的topic
是ORB_SLAM/pose
,如果用的不是D435i
,比如zed双目相机,可以自行修改。
2.2 修改CMakeLists.txt
由于新增了发布功能的代码文件,那对应的CMakeLists.txt也需要新增对应的编译和链接的设置,如下所示,在ORB_SLAM2/Examples/ROS/ORB_SLAM2/CMakeLists.txt
文件的结尾新增:
# Node for d435i_stereo camera
# 设置了编译的代码文件`d435i_stereo.cc`和可执行文件的名字
rosbuild_add_executable(D435i_Stereo
src/d435i_stereo.cc
)target_link_libraries(D435i_Stereo
${LIBS}
)
2.3 新增配置文件D435i.yaml
同时也要新增对应的配置文件D435i.yaml
,可新增到ORB_SLAM2/Examples/Stereo/D435i.yaml
,文件类似ORB_SLAM2/Examples/Stereo/EuRoC.yaml
,如下所示,主要修改第一部分的内参部分(fx,fy,cx,cy
)即可,相机的内参获取方法,可通过roslaunch realsense2_camera rs_camera.launch
启动相机后,再通过rostopic echo /camera/infra1/camera_info
来获取。
%YAML:1.0#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 427.03680419921875
Camera.fy: 427.03680419921875
Camera.cx: 427.3993835449219
Camera.cy: 236.4639129638672Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0Camera.width: 848
Camera.height: 480# Camera frames per second
Camera.fps: 15.0# stereo baseline times fx
Camera.bf: 50.0# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1# Close/Far threshold. Baseline times.
ThDepth: 35#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 480
LEFT.width: 752
LEFT.D: !!opencv-matrixrows: 1cols: 5dt: ddata:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
LEFT.K: !!opencv-matrixrows: 3cols: 3dt: ddata: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrixrows: 3cols: 3dt: ddata: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
LEFT.P: !!opencv-matrixrows: 3cols: 4dt: ddata: [435.2046959714599, 0, 367.4517211914062, 0, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]RIGHT.height: 480
RIGHT.width: 752
RIGHT.D: !!opencv-matrixrows: 1cols: 5dt: ddata:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
RIGHT.K: !!opencv-matrixrows: 3cols: 3dt: ddata: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
RIGHT.R: !!opencv-matrixrows: 3cols: 3dt: ddata: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
RIGHT.P: !!opencv-matrixrows: 3cols: 4dt: ddata: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
3 编译运行和结果
3.1 编译运行
全部修改后,可回到ORB_SLAM2
工程目录下,重新执行命令进行编译:
# chmod 之前执行过可忽略
chmod +x build_ros.sh
./build_ros.sh
编译完成后,首先连接D435i
相机到电脑上(USB3.0
),然后执行命令启动D435i
相机:
source /catkin_rs/devel/setup.bash
roslaunch realsense2_camera rs_camera.launch
然后再新开终端,执行D435i_Stereo
:
# ORB_SLAM2工程目录下
rosrun ORB_SLAM2 D435i_Stereo Vocabulary/ORBvoc.txt Examples/Stereo/D435i.yaml false
3.2 结果
执行上述命令后,在加载完词袋后,会自动打开两个可视化界面:
ORB-SLAM2: Current Frame
ORB-SLAM2: Map Viewer
可以用rostopic list
可查看到已经发出的位姿topic
:
/ORB_SLAM/path
/ORB_SLAM/pose
也可以用rostopic echo /ORB_SLAM/pose
查看具体的位姿信息:
header: seq: 3287stamp: secs: 0nsecs: 0frame_id: "path"
pose: position: x: 0.0335485860705y: -0.0102641582489z: -0.0411500893533orientation: x: -0.042415473676y: -0.00852415898276z: -0.015283392766w: 0.998946787478
至此,成功用D435i
相机的双目IR
相机作为输入,运行ROS
版ORB-SLAM2
,最后发出pose
的rostopic
。
3.3 可能出现的问题
问题1:
如果如下所示的问题,启动后很快自动关闭,可能是特征点太少的原因,调整相机的朝向,保证相机视野范围内多一点特征:
terminate called after throwing an instance of 'cv::Exception'what(): /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/core/src/matrix.cpp:483: error: (-215) 0 <= _rowRange.start && _rowRange.start <= _rowRange.end && _rowRange.end <= m.rows in function MatAborted (core dumped)
Reference:
- https://github.com/raulmur/ORB_SLAM2
⭐️👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍🌔
相关文章:

ORB-SLAM2学习笔记6之D435i双目IR相机运行ROS版ORB-SLAM2并发布位姿pose的rostopic
文章目录 0 引言1 D435i相机配置2 新增发布双目位姿功能2.1 新增d435i_stereo.cc代码2.2 修改CMakeLists.txt2.3 新增配置文件D435i.yaml 3 编译运行和结果3.1 编译运行3.2 结果3.3 可能出现的问题 0 引言 ORB-SLAM2学习笔记1已成功编译安装ROS版本ORB-SLAM2到本地,…...

【数据结构与算法——TypeScript】哈希表
【数据结构与算法——TypeScript】 哈希表(HashTable) 哈希表介绍和特性 哈希表是一种非常重要的数据结构,但是很多学习编程的人一直搞不懂哈希表到底是如何实现的。 在这一章节中,我门就一点点来实现一个自己的哈希表。通过实现来理解哈希表背后的原理…...

JavaScript 中常用简写语法技巧总结
分享一些自己常用的js简写技巧,长期更新,会着重挑选一些实用的简写技巧,使自己的代码更简洁优雅~ 这里只会收集一些大多数人不知道的用法,但是确实能提高自己的编码技巧,像ES6那些基础的简写语法或者是三目运算符代替i…...

漫画算法做题笔记
诸神缄默不语-个人CSDN博文目录 哦这是我三年前写的,我现在Java语法都快忘光了…… 反正之前的博文也发一下好了。这个因为我当年是用有道云笔记而不是直接用CSDN编辑器写的,所以后面有些内容写乱了,因为我现在猛的一看有点看不懂࿰…...

JDBC学习笔记
1 JDBC简介 1.1 前言 当谈论JDBC时,我们可以将其看作是一种用于Java程序与数据库进行通信的方式。如果你想编写一个Java程序,并且希望能够连接到数据 库、执行查询或更新数据,JDBC就是你需要的工具。 JDBC提供了一组类和接口,…...

亚信科技AntDB数据库与库瀚存储方案完成兼容性互认证,联合方案带来约20%性能提升
近日,亚信科技AntDB数据库与苏州库瀚信息科技有限公司自主研发的RISC-V数据库存储解决方案进行了产品兼容测试。经过双方团队的严格测试,亚信科技AntDB数据库与库瀚数据库存储解决方案完全兼容、运行稳定。除高可用性测试外,双方进一步开展TP…...

【MySQL】基础知识(一)
MySQL基础知识(一) 文章目录 MySQL基础知识(一)00 MySQL安装01 数据库介绍1.1 什么是数据库1.2数据库分类 02 SQL分类03 数据库操作3.1显示数据库3.2创建数据库3.3选中数据库3.4删除数据库 04 常用数据类型4.1数值类型4.2字符串类…...

Ansible专栏目录
我的博客:www.itwk.cc 希望能够给大家带来帮助! 1、什么是Ansible?Ansible 简介及核心概念详解 https://blog.csdn.net/qq_34185638/article/details/131079320 2、Ansible Inventory 主机清单的作用、使用方法及示例详解 https://blog.cs…...

【locust】使用locust + boomer实现对接口的压测
目录 背景 环境安装 脚本编写 master slave节点(golang/boomer) 问题 资料获取方法 背景 很早之前,考虑单机执行能力,使用locust做过公司短信网关的压测工作,后来发现了一个golang版本的locust,性能…...

亿欧智库:2023中国宠物行业新趋势洞察报告(附下载)
关于报告的所有内容,公众【营销人星球】获取下载查看 核心观点 户外赛道本质上迎合了全球共性需求的增长,从养宠意愿的转化到养宠生活的需求,多层次的需求推动行业发展新趋势 从需求端进行分析,可以将养宠意愿的转化分为三个层…...

时序数据库 TDengine 与 WhaleStudio 完成相互兼容性测试认证
近年来,开源及其价值获得社会各界的广泛认可,无论是国家政策导向还是企业数字化转型,都在加速拥抱开源。对于如操作系统、数据库等基础软件来说,开源更是成为驱动技术创新的有力途径。 在此背景下,近日,涛…...

Spring-1-深入理解Spring XML中的依赖注入(DI):简化Java应用程序开发
学习目标 前两篇文章我们介绍了什么是Spring,以及Spring的一些核心概念,并且快速快发一个Spring项目,以及详细讲解IOC,今天详细介绍一些DI(依赖注入) 能够配置setter方式注入属性值 能够配置构造方式注入属性值 能够理解什么是自动装配 一、…...

负载均衡–HAProxy安装及搭建tidb数据库负载服务
作为一名开发人员,随着经验的增加和技术的沉淀,需要提高自己架构方面的知识,同时对于一个企业来说,搭建一套高可用、高性能的技术架构,对于公司的业务开展和提高服务的性能也是大有裨益的。本文重点从软件安装和搭建ti…...

Django各种缓存的配置
Django提供了多种缓存后端,如内存缓存、文件缓存、数据库缓存、Memcached和Redis等。根据项目需求选择合适的缓存后端。 settings配置 在Django项目的settings.py文件中,找到或新增CACHES配置项。根据所选的缓存后端,配置相应的参数。以下是…...

实现跨域的几种方式
原理 前后端的分离导致了跨域的产生 跨域的三要素:协议 域名 端口 三者有一个不同即产生跨域 例如: http://www.csdn.com https://www.csdn.com 由于协议不同,端口不同而产生跨域 注:http的默认端口80,https的默…...

OpenCV: 对“google::protobuf::internal::Release_CompareAndSwap”的未定义
解决办法: 需要在文件 protobuf/src/google/protobuf/stubs/atomicops_internals_generic_gcc.h 中的以下补丁 inline Atomic64 Release_CompareAndSwap(volatile Atomic64* ptr, Atomic64 old_value, …...

无涯教程-Perl - References(引用)
Perl引用是一个标量数据类型,该数据类型保存另一个值的位置,该值可以是标量,数组或哈希。 创建引用 变量,子程序或值创建引用很容易,方法是在其前面加上反斜杠,如下所示: $scalarref \$foo; $arrayref …...

马斯克收购AI.com域名巩固xAI公司地位;如何评估大型语言模型的性能
🦉 AI新闻 🚀 AI拍照小程序妙鸭相机上线商业工作站并邀请摄影师进行内测 摘要:AI拍照小程序妙鸭相机将上线面向商业端的工作站,并邀请摄影师进行模板设计的内测。妙鸭相机希望为行业提供更多生态产品,扩大行业规模&a…...

uni-app:实现点击按钮出现底部弹窗(uni.showActionSheet+自定义)
一、通过uni.showActionSheet实现底部选择 效果 代码 <template><view><button click"showActionsheet">点击打开弹窗</button></view> </template><script> export default {methods: {showActionsheet() {uni.showAct…...

flume系列之:监控zookeeper的flume配置写入节点,新增和删除flume agent节点,通过ansible自动部署和卸载flume agent
flume系列之:监控zookeeper的flume配置写入节点,新增和删除flume agent节点,通过ansible自动部署和卸载flume agent 一、相关技术二、流程梳理三、部署和删除flume agent效果四、监控zookeeper节点五、新增zookeeper节点部署flume agent六、删除zookeeper节点删除flume agen…...

了解以太网通信中的九阳神功 - SOME/IP协议
智能座舱SOME/IP通信 概述SOME/IP基础协议SOME/IP SD协议通信行为流程开机流程关机行为行为时序总结概述 SOME/IP协议是目前国内座舱SOA化应用比较广泛的一种ECU或车辆网络内设备之间交换数据的网络通信协议。它允许不同车辆组件,如发动机控制单元、信息娱乐系统、车身控制模…...

redis List类型命令
在Redis中,List(列表)是一种有序的、可重复的数据结构,它支持插入、删除和获取元素的操作。以下是一些常见的Redis List类型命令: LPUSH:将一个或多个值从列表的左侧插入。LPUSH key value1 value2 ...其中…...

【博客685】prometheus 出现NaN场景以及如何去除干扰(Not a Number)
prometheus 出现NaN场景以及如何去除干扰(Not a Number) 1、在prometheus中使用NaN来表示无效数值或者结果 场景: 一些监控系统使用 NaN 作为空值或缺失值,但在 Prometheus 中 NaN 只是另一个浮点值。Prometheus 表示缺失数据的方式是让数据缺失。Prom…...

【计算机网络】网络层协议 -- ICMP协议
文章目录 1. ICMP协议简介2. ICMP协议格式3. ping命令4. ping命令与端口号没有关系!!!5. traceroute命令 1. ICMP协议简介 ICMP(Internet Control Message Protocol,控制报文协议),用于在IP主机…...

机器学习---facebook的案例学习
import pandas as pd import matplotlib.pyplot as plt import seaborn as sbn from sklearn.model_selection import train_test_split,GridSearchCV from sklearn.preprocessing import StandardScaler from sklearn.neighbors import KNeighborsClassifier # 使用pandas读…...

OpenMMLab MMDetectionV3.1.0-SAM(环境安装、模型测试、训练以及模型后处理工具)
OpenMMLab Playground 概况 当前通用目标检测的研究方向正在朝着大型多模态模型发展。除了图像输入之外,最近的研究成果还结合了文本模式来提高性能。添加文本模态后,通用检测算法的一些非常好的属性开始出现,例如: 可以利用大量…...

ios_base::out和ios::out、ios_base::in和ios::in、ios_base::app和ios::app等之间有什么区别吗?
2023年8月2日,周三晚上 今天我看到了这样的两行代码: std::ofstream file("example.txt", std::ios_base::out);std::ofstream file("example.txt", std::ios::out);这让我产生了几个疑问: 为什么有时候用ios_base::o…...

PostgreSQL 使用SQL
发布主题 设置发布为true 这个语句是针对 PostgreSQL 数据库中的逻辑复制功能中的逻辑发布(Logical Publication)进行设置的。 PostgreSQL 中,逻辑复制是一种基于逻辑日志的复制方法,允许将数据更改从一个数据库实例复制到另一…...

Shell编程基础(十四)文本三剑客(grep)
文本三剑客(grep) 使用场景基本使用返回值参数 使用场景 主要用于查找,过滤文本数据;该数据可以来自文件,也可以来自管道流等等。 grep除了原有的实现,后来还出现了以下扩展实现 egrep:支持扩展…...

Linux root用户执行修改密码命令,提示 Permission denied
问题 linux系统中(ubuntu20),root用户下执行passwd命令,提示 passwd: Permission denied ,如下图: 排查 1.执行 ll /usr/bin/passwd ,查看文件权限是否正确,正常情况是 -rwsr-xr…...