autoware lidar_localizer包下的ndt_matching节点的学习

激光雷达定位

自身定位对于自动驾驶汽车来说非常重要,常见的机器人定位方法有视觉slam方法(即时定位与地图构建),根据激光雷达实时扫描到的点云图构建地图,然后进行定位的方法。但是在自动驾驶具有高速移动,高安全性的要求下,对该方法的延时要求较高。而另一种定位方法位ndt(正态分布变换)地图匹配方法,则是在已有的高精度地图的基础上,将扫描到的点云地图进行高维变换,找出匹配度最高的转换关系,得到定位位置。autoware采用的是ndt地图匹配定位算法,其中能够选择是否需要gnss进行协同定位。

ndt算法:

先根据参考数据(reference scan)来构建多维变量的正态分布,如果变换参数能使得两幅激光数据匹配的很好,那么变换点在参考系中的概率密度将会很大。因此,可以考虑用优化的方法求出使得概率密度之和最大的变换参数,此时两幅激光点云数据将匹配的最好。

  1. 将参考点云(reference scan)所占的空间划分成体素,并计算每个网格的多维正态分布参数
  2. 将点云投票到各个格子
  3. 计算格子的正态分布PDF参数
  4. 将第二幅scan的每个点按转移矩阵T的变换
  5. 第二幅scan的点落于reference的哪个 格子,计算响应的概率分布函数
  6. 求所有点的最优值

ndt_matching

lidar_localizer节点的launch文件如图所示,其中主要查看ndt_matching.launch文件,该文件,描述了启动节点,以及相应的参数配置。
在这里插入图片描述
launch文件主要启动lidar_localizer功能包下的ndt_matching节点文件。参数设置主要包括method_type,use_gnss,use_odom,use_imu,imu_upside_down等。

<launch><arg name="method_type" default="0" /> <!-- pcl_generic=0, pcl_anh=1, pcl_anh_gpu=2, pcl_openmp=3 --><arg name="use_gnss" default="1" /><arg name="use_odom" default="false" /><arg name="use_imu" default="false" /><arg name="imu_upside_down" default="false" /><arg name="imu_topic" default="/imu_raw" /><arg name="queue_size" default="1" /><arg name="offset" default="linear" /><arg name="get_height" default="false" /><arg name="use_local_transform" default="false" /><arg name="sync" default="false" /><arg name="output_log_data" default="false" /><node pkg="lidar_localizer" type="ndt_matching" name="ndt_matching" output="log"><param name="method_type" value="$(arg method_type)" /><param name="use_gnss" value="$(arg use_gnss)" /><param name="use_odom" value="$(arg use_odom)" /><param name="use_imu" value="$(arg use_imu)" /><param name="imu_upside_down" value="$(arg imu_upside_down)" /><param name="imu_topic" value="$(arg imu_topic)" /><param name="queue_size" value="$(arg queue_size)" /><param name="offset" value="$(arg offset)" /><param name="get_height" value="$(arg get_height)" /><param name="use_local_transform" value="$(arg use_local_transform)" /><param name="output_log_data" value="$(arg output_log_data)" /><remap from="/points_raw" to="/sync_drivers/points_raw" if="$(arg sync)" /></node>
</launch>

主要分析ndt_matching.cpp节点。首先看main函数,初始化并命名节点ndt_matching,然后初始化线程互斥锁,为后续多线程操作做准备。接着初始化共有句柄nh,以及私有句柄private_nh。

int main(int argc, char** argv)
{ros::init(argc, argv, "ndt_matching");pthread_mutex_init(&mutex, NULL);ros::NodeHandle nh;ros::NodeHandle private_nh("~");node_status_publisher_ptr_ = std::make_shared<autoware_health_checker::NodeStatusPublisher>(nh,private_nh);//声明节点状态的智能指针node_status_publisher_ptr_->ENABLE();node_status_publisher_ptr_->NODE_ACTIVATE();

然后设置了日志文件的名称

private_nh.getParam("output_log_data", _output_log_data);if(_output_log_data){char buffer[80];std::time_t now = std::time(NULL);std::tm* pnow = std::localtime(&now);std::strftime(buffer, 80, "%Y%m%d_%H%M%S", pnow);std::string directory_name = "/tmp/Autoware/log/ndt_matching";filename = directory_name + "/" + std::string(buffer) + ".csv";boost::filesystem::create_directories(boost::filesystem::path(directory_name));ofs.open(filename.c_str(), std::ios::app);}

tl_btol表示点之间的平移关系,rot_x_btol描述的是描述关于x轴的旋转关系,_tf_roll为绕x轴的旋转角度,rot_y_btol,rot_z_btol同样表示y轴预z轴的旋转角度。tf_btol为位姿变换关系静态变换矩阵,由坐标*旋转来表示。

  Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z);                 // tl: translation 平移关系Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX());  // rot: rotation 描述关于x轴的旋转关系,_tf_roll为绕x轴的旋转角度Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY());Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ());tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix();

发布车辆,惯导,例程及ndt预测位置。

predict_pose_pub = nh.advertise<geometry_msgs::PoseStamped>("/predict_pose", 10);//发布预测位资的消息predict_pose_imu_pub = nh.advertise<geometry_msgs::PoseStamped>("/predict_pose_imu", 10);predict_pose_odom_pub = nh.advertise<geometry_msgs::PoseStamped>("/predict_pose_odom", 10);predict_pose_imu_odom_pub = nh.advertise<geometry_msgs::PoseStamped>("/predict_pose_imu_odom", 10);ndt_pose_pub = nh.advertise<geometry_msgs::PoseStamped>("/ndt_pose", 10);

通过回调函数订阅参数,初始位置,过滤点集等消息。

  ros::Subscriber param_sub = nh.subscribe("config/ndt", 10, param_callback);ros::Subscriber gnss_sub = nh.subscribe("gnss_pose", 10, gnss_callback);//  ros::Subscriber map_sub = nh.subscribe("points_map", 1, map_callback);ros::Subscriber initialpose_sub = nh.subscribe("initialpose", 10, initialpose_callback);ros::Subscriber points_sub = nh.subscribe("filtered_points", _queue_size, points_callback);ros::Subscriber odom_sub = nh.subscribe("/vehicle/odom", _queue_size * 10, odom_callback);ros::Subscriber imu_sub = nh.subscribe(_imu_topic.c_str(), _queue_size * 10, imu_callback);

然后看convertPoseIntoRelativeCoordinate这个函数,它返回的是位置,主要是将位置坐标转换到参考坐标系。首先声明存储目标姿态的四元数。四元数是ros里用来表示3D刚体物体姿态。无人汽车在空间中的位资主要有自身的坐标位置(x,y,z)以及绕着参考坐标系坐标轴的旋转角度。通常描述旋转量有欧拉角,还有四元数,而欧拉角表示的是刚体绕着坐标轴的旋转角度,欧拉角的优点具有直观性,但是采用欧拉角会使得描述刚体处于万向锁的情况,所以欧拉角适用于验证。而四元数类似于复数,其具有一个实部和三个虚部,四元数可以表示空间中任意旋转。

通过调用setRPY函数能够按照固定轴xyz来设置旋转角度,并且存储表示目标位置的向量,然后作为参数传入表示目标位资的target_tf对象的构造函数。

static pose convertPoseIntoRelativeCoordinate(const pose &target_pose, const pose &reference_pose)//将位置转换到相对坐标系
{tf::Quaternion target_q;//目标的四元数target_q.setRPY(target_pose.roll, target_pose.pitch, target_pose.yaw);//按照固定轴来设置旋转角度xyz轴下tf::Vector3 target_v(target_pose.x, target_pose.y, target_pose.z);//目标位置向量tf::Transform target_tf(target_q, target_v);//声明存放目标位资转换信息(平移+旋转)的对象,并初始化构造函数。tf::Quaternion reference_q;//参照四元数reference_q.setRPY(reference_pose.roll, reference_pose.pitch, reference_pose.yaw);//设置xyz绕轴转动角度tf::Vector3 reference_v(reference_pose.x, reference_pose.y, reference_pose.z);//设置参考位置向量tf::Transform reference_tf(reference_q, reference_v);tf::Transform trans_target_tf = reference_tf.inverse() * target_tf;//inverse返回变换的逆矩阵如pose trans_target_pose;//训练目标的坐标trans_target_pose.x = trans_target_tf.getOrigin().getX();//返回x值trans_target_pose.y = trans_target_tf.getOrigin().getY();trans_target_pose.z = trans_target_tf.getOrigin().getZ();tf::Matrix3x3 tmp_m(trans_target_tf.getRotation());tmp_m.getRPY(trans_target_pose.roll, trans_target_pose.pitch, trans_target_pose.yaw);return trans_target_pose;
}//返回转换的目标位置

参数订阅者param_sub通过config/ndt话题,当接收到配置信息的时候调用回调函数param_callback来进行参数配置,其中主要配置的有初始化位置。以及是否使用gnss时参数配置有所不同。

static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& input)//参数回调函数完成参数的初始化
{if (_use_gnss != input->init_pos_gnss){init_pos_set = 0;}else if (_use_gnss == 0 &&(initial_pose.x != input->x || initial_pose.y != input->y || initial_pose.z != input->z ||initial_pose.roll != input->roll || initial_pose.pitch != input->pitch || initial_pose.yaw != input->yaw)){init_pos_set = 0;}_use_gnss = input->init_pos_gnss;// Setting parameters

位姿初始化以及速度的初始化。

 localizer_pose.x = initial_pose.x;localizer_pose.y = initial_pose.y;localizer_pose.z = initial_pose.z;localizer_pose.roll = initial_pose.roll;localizer_pose.pitch = initial_pose.pitch;localizer_pose.yaw = initial_pose.yaw;previous_pose.x = initial_pose.x;previous_pose.y = initial_pose.y;previous_pose.z = initial_pose.z;previous_pose.roll = initial_pose.roll;previous_pose.pitch = initial_pose.pitch;previous_pose.yaw = initial_pose.yaw;current_pose.x = initial_pose.x;current_pose.y = initial_pose.y;current_pose.z = initial_pose.z;current_pose.roll = initial_pose.roll;current_pose.pitch = initial_pose.pitch;current_pose.yaw = initial_pose.yaw;current_velocity = 0;current_velocity_x = 0;current_velocity_y = 0;current_velocity_z = 0;angular_velocity = 0;current_pose_imu.x = 0;current_pose_imu.y = 0;current_pose_imu.z = 0;current_pose_imu.roll = 0;current_pose_imu.pitch = 0;current_pose_imu.yaw = 0;current_velocity_imu_x = current_velocity_x;current_velocity_imu_y = current_velocity_y;current_velocity_imu_z = current_velocity_z;init_pos_set = 1;

ros::Subscriber gnss_sub = nh.subscribe(“gnss_pose”, 10, gnss_callback)此处通过gnss_pose话题订阅惯导的位置信息。当接收到消息之后,惯导回调函数获取当前惯导的gps位置和位姿数据,如果使用gnss,并且初始位置设置为0或者fitness_score大于或等于500()时,则进行gnss重定位,即将位置更新为当前的位姿,并计算当前位置与先前位置的偏差。

static void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input)
{tf::Quaternion gnss_q(input->pose.orientation.x, input->pose.orientation.y, input->pose.orientation.z,input->pose.orientation.w);tf::Matrix3x3 gnss_m(gnss_q);//讲位置四元数转换为旋转矩阵pose current_gnss_pose;current_gnss_pose.x = input->pose.position.x;current_gnss_pose.y = input->pose.position.y;current_gnss_pose.z = input->pose.position.z;gnss_m.getRPY(current_gnss_pose.roll, current_gnss_pose.pitch, current_gnss_pose.yaw);//得到当前的RPY姿态角度static pose previous_gnss_pose = current_gnss_pose;ros::Time current_gnss_time = input->header.stamp;//记录当前gnss的时间static ros::Time previous_gnss_time = current_gnss_time;if ((_use_gnss == 1 && init_pos_set == 0) || fitness_score >= 500.0)//{previous_pose.x = previous_gnss_pose.x;previous_pose.y = previous_gnss_pose.y;previous_pose.z = previous_gnss_pose.z;previous_pose.roll = previous_gnss_pose.roll;previous_pose.pitch = previous_gnss_pose.pitch;previous_pose.yaw = previous_gnss_pose.yaw;current_pose.x = current_gnss_pose.x;current_pose.y = current_gnss_pose.y;current_pose.z = current_gnss_pose.z;current_pose.roll = current_gnss_pose.roll;current_pose.pitch = current_gnss_pose.pitch;current_pose.yaw = current_gnss_pose.yaw;current_pose_imu = current_pose_odom = current_pose_imu_odom = current_pose;diff_x = current_pose.x - previous_pose.x;diff_y = current_pose.y - previous_pose.y;diff_z = current_pose.z - previous_pose.z;diff_yaw = current_pose.yaw - previous_pose.yaw;diff = sqrt(diff_x * diff_x + diff_y * diff_y + diff_z * diff_z);const pose trans_current_pose = convertPoseIntoRelativeCoordinate(current_pose, previous_pose);const double diff_time = (current_gnss_time - previous_gnss_time).toSec();current_velocity = (diff_time > 0) ? (diff / diff_time) : 0;current_velocity =  (trans_current_pose.x >= 0) ? current_velocity : -current_velocity;current_velocity_x = (diff_time > 0) ? (diff_x / diff_time) : 0;current_velocity_y = (diff_time > 0) ? (diff_y / diff_time) : 0;current_velocity_z = (diff_time > 0) ? (diff_z / diff_time) : 0;angular_velocity = (diff_time > 0) ? (diff_yaw / diff_time) : 0;current_accel = 0.0;current_accel_x = 0.0;current_accel_y = 0.0;current_accel_z = 0.0;init_pos_set = 1;}

然后是points_callback匹配模块

static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input)
{if (map_loaded == 1 && init_pos_set == 1) //map_loaded和init_pos_set默认都为0,收到地图后map_loaded为1,参数初始化或者设置位置之后init_pos_set为1{matching_start = std::chrono::system_clock::now();//获取当前系统时间static tf::TransformBroadcaster br;//tf广播tf::Transform transform;/*predict 速度积分预估previous 上一时刻ndt 正态分布匹配出来的base_link位置current 当前时刻最终定位localizer 正态分布匹配出来的lidar位置*/tf::Quaternion predict_q, ndt_q, current_q, localizer_q;pcl::PointXYZ p;pcl::PointCloud<pcl::PointXYZ> filtered_scan;ros::Time current_scan_time = input->header.stamp;static ros::Time previous_scan_time = current_scan_time;pcl::fromROSMsg(*input, filtered_scan);pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>(filtered_scan));int scan_points_num = filtered_scan_ptr->size();//初始化矩阵Eigen::Matrix4f t(Eigen::Matrix4f::Identity());   // base_linkEigen::Matrix4f t2(Eigen::Matrix4f::Identity());  // localizerstd::chrono::time_point<std::chrono::system_clock> align_start, align_end, getFitnessScore_start,getFitnessScore_end;static double align_time, getFitnessScore_time = 0.0;pthread_mutex_lock(&mutex);//加载配准点云if (_method_type == MethodType::PCL_GENERIC)ndt.setInputSource(filtered_scan_ptr);else if (_method_type == MethodType::PCL_ANH)anh_ndt.setInputSource(filtered_scan_ptr);
#ifdef CUDA_FOUNDelse if (_method_type == MethodType::PCL_ANH_GPU)anh_gpu_ndt_ptr->setInputSource(filtered_scan_ptr);
#endif
#ifdef USE_PCL_OPENMPelse if (_method_type == MethodType::PCL_OPENMP)omp_ndt.setInputSource(filtered_scan_ptr);
#endif// Guess the initial gross estimation of the transformation// 当前帧的雷达时间和上一帧的雷达时间间隔double diff_time = (current_scan_time - previous_scan_time).toSec();//速度积分,上一时刻速度*间隔时间if (_offset == "linear"){offset_x = current_velocity_x * diff_time;offset_y = current_velocity_y * diff_time;offset_z = current_velocity_z * diff_time;offset_yaw = angular_velocity * diff_time;}else if (_offset == "quadratic"){offset_x = (current_velocity_x + current_accel_x * diff_time) * diff_time;offset_y = (current_velocity_y + current_accel_y * diff_time) * diff_time;offset_z = current_velocity_z * diff_time;offset_yaw = angular_velocity * diff_time;}else if (_offset == "zero"){offset_x = 0.0;offset_y = 0.0;offset_z = 0.0;offset_yaw = 0.0;}predict_pose.x = previous_pose.x + offset_x;predict_pose.y = previous_pose.y + offset_y;predict_pose.z = previous_pose.z + offset_z;predict_pose.roll = previous_pose.roll;predict_pose.pitch = previous_pose.pitch;predict_pose.yaw = previous_pose.yaw + offset_yaw;if (_use_imu == true && _use_odom == true)imu_odom_calc(current_scan_time);if (_use_imu == true && _use_odom == false)imu_calc(current_scan_time);if (_use_imu == false && _use_odom == true)odom_calc(current_scan_time);pose predict_pose_for_ndt;if (_use_imu == true && _use_odom == true)predict_pose_for_ndt = predict_pose_imu_odom;else if (_use_imu == true && _use_odom == false)predict_pose_for_ndt = predict_pose_imu;else if (_use_imu == false && _use_odom == true)predict_pose_for_ndt = predict_pose_odom;elsepredict_pose_for_ndt = predict_pose;//最终选择//提供了点云配准变换,由之前的(x,y,z,roll,pitch,yaw)求出旋转矩阵Eigen::Translation3f init_translation(predict_pose_for_ndt.x, predict_pose_for_ndt.y, predict_pose_for_ndt.z);Eigen::AngleAxisf init_rotation_x(predict_pose_for_ndt.roll, Eigen::Vector3f::UnitX());Eigen::AngleAxisf init_rotation_y(predict_pose_for_ndt.pitch, Eigen::Vector3f::UnitY());Eigen::AngleAxisf init_rotation_z(predict_pose_for_ndt.yaw, Eigen::Vector3f::UnitZ());Eigen::Matrix4f init_guess = (init_translation * init_rotation_z * init_rotation_y * init_rotation_x) * tf_btol;pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);if (_method_type == MethodType::PCL_GENERIC)//默认_method_type为0{align_start = std::chrono::system_clock::now();ndt.align(*output_cloud, init_guess);//进行配准打分和输出align_end = std::chrono::system_clock::now();has_converged = ndt.hasConverged();//正态分布收敛值t = ndt.getFinalTransformation();//得出的变换矩阵iteration = ndt.getFinalNumIteration();//获取计算对齐所需的迭代次数getFitnessScore_start = std::chrono::system_clock::now();fitness_score = ndt.getFitnessScore();//匹配分数getFitnessScore_end = std::chrono::system_clock::now();trans_probability = ndt.getTransformationProbability();//转化概率}else if (_method_type == MethodType::PCL_ANH){align_start = std::chrono::system_clock::now();anh_ndt.align(init_guess);align_end = std::chrono::system_clock::now();has_converged = anh_ndt.hasConverged();t = anh_ndt.getFinalTransformation();iteration = anh_ndt.getFinalNumIteration();getFitnessScore_start = std::chrono::system_clock::now();fitness_score = anh_ndt.getFitnessScore();getFitnessScore_end = std::chrono::system_clock::now();trans_probability = anh_ndt.getTransformationProbability();}
#ifdef CUDA_FOUNDelse if (_method_type == MethodType::PCL_ANH_GPU){align_start = std::chrono::system_clock::now();anh_gpu_ndt_ptr->align(init_guess);align_end = std::chrono::system_clock::now();has_converged = anh_gpu_ndt_ptr->hasConverged();t = anh_gpu_ndt_ptr->getFinalTransformation();iteration = anh_gpu_ndt_ptr->getFinalNumIteration();getFitnessScore_start = std::chrono::system_clock::now();fitness_score = anh_gpu_ndt_ptr->getFitnessScore();getFitnessScore_end = std::chrono::system_clock::now();trans_probability = anh_gpu_ndt_ptr->getTransformationProbability();}
#endif
#ifdef USE_PCL_OPENMPelse if (_method_type == MethodType::PCL_OPENMP){align_start = std::chrono::system_clock::now();omp_ndt.align(*output_cloud, init_guess);align_end = std::chrono::system_clock::now();has_converged = omp_ndt.hasConverged();t = omp_ndt.getFinalTransformation();iteration = omp_ndt.getFinalNumIteration();getFitnessScore_start = std::chrono::system_clock::now();fitness_score = omp_ndt.getFitnessScore();getFitnessScore_end = std::chrono::system_clock::now();trans_probability = omp_ndt.getTransformationProbability();}
#endif//配准打分的时间align_time = std::chrono::duration_cast<std::chrono::microseconds>(align_end - align_start).count() / 1000.0;t2 = t * tf_btol.inverse();//tf_btol.inverse():机器人到雷达的静态变换矩阵   t:雷达到点云的变换矩阵//获取匹配分数的时间getFitnessScore_time =std::chrono::duration_cast<std::chrono::microseconds>(getFitnessScore_end - getFitnessScore_start).count() /1000.0;pthread_mutex_unlock(&mutex);tf::Matrix3x3 mat_l;  // localizermat_l.setValue(static_cast<double>(t(0, 0)), static_cast<double>(t(0, 1)), static_cast<double>(t(0, 2)),static_cast<double>(t(1, 0)), static_cast<double>(t(1, 1)), static_cast<double>(t(1, 2)),static_cast<double>(t(2, 0)), static_cast<double>(t(2, 1)), static_cast<double>(t(2, 2)));// Update localizer_poselocalizer_pose.x = t(0, 3);localizer_pose.y = t(1, 3);localizer_pose.z = t(2, 3);mat_l.getRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw, 1);tf::Matrix3x3 mat_b;  // base_linkmat_b.setValue(static_cast<double>(t2(0, 0)), static_cast<double>(t2(0, 1)), static_cast<double>(t2(0, 2)),static_cast<double>(t2(1, 0)), static_cast<double>(t2(1, 1)), static_cast<double>(t2(1, 2)),static_cast<double>(t2(2, 0)), static_cast<double>(t2(2, 1)), static_cast<double>(t2(2, 2)));// Update ndt_posendt_pose.x = t2(0, 3);ndt_pose.y = t2(1, 3);ndt_pose.z = t2(2, 3);mat_b.getRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw, 1);// Calculate the difference between ndt_pose and predict_pose// 计算ndt_pose和predict_pose之间的差异//predict_pose_for_ndt为这次位置的速度积分值predict_pose_error = sqrt((ndt_pose.x - predict_pose_for_ndt.x) * (ndt_pose.x - predict_pose_for_ndt.x) +(ndt_pose.y - predict_pose_for_ndt.y) * (ndt_pose.y - predict_pose_for_ndt.y) +(ndt_pose.z - predict_pose_for_ndt.z) * (ndt_pose.z - predict_pose_for_ndt.z));if (predict_pose_error <= PREDICT_POSE_THRESHOLD)//PREDICT_POSE_THRESHOLD默认值为0.5{use_predict_pose = 0;}else{use_predict_pose = 1;}use_predict_pose = 0;if (use_predict_pose == 0)//如果为0,说明速度积分值和计算匹配值相近,则说明定位没有跳跃,设当前位置为计算匹配值{current_pose.x = ndt_pose.x;current_pose.y = ndt_pose.y;current_pose.z = ndt_pose.z;current_pose.roll = ndt_pose.roll;current_pose.pitch = ndt_pose.pitch;current_pose.yaw = ndt_pose.yaw;}else//如果为1,说明预估值和计算匹配值相差教导,则说明定位出现了跳跃,设当前位置为速度积分值{current_pose.x = predict_pose_for_ndt.x;current_pose.y = predict_pose_for_ndt.y;current_pose.z = predict_pose_for_ndt.z;current_pose.roll = predict_pose_for_ndt.roll;current_pose.pitch = predict_pose_for_ndt.pitch;current_pose.yaw = predict_pose_for_ndt.yaw;}// Compute the velocity and acceleration//计算速度和加速度//位置差异 = 当前位置 - 上一位置diff_x = current_pose.x - previous_pose.x;diff_y = current_pose.y - previous_pose.y;diff_z = current_pose.z - previous_pose.z;diff_yaw = calcDiffForRadian(current_pose.yaw, previous_pose.yaw);diff = sqrt(diff_x * diff_x + diff_y * diff_y + diff_z * diff_z);//当前速度 = 位置差异/时间间隔current_velocity = (diff_time > 0) ? (diff / diff_time) : 0;current_velocity_x = (diff_time > 0) ? (diff_x / diff_time) : 0;current_velocity_y = (diff_time > 0) ? (diff_y / diff_time) : 0;current_velocity_z = (diff_time > 0) ? (diff_z / diff_time) : 0;angular_velocity = (diff_time > 0) ? (diff_yaw / diff_time) : 0;current_pose_imu.x = current_pose.x;current_pose_imu.y = current_pose.y;current_pose_imu.z = current_pose.z;current_pose_imu.roll = current_pose.roll;current_pose_imu.pitch = current_pose.pitch;current_pose_imu.yaw = current_pose.yaw;current_velocity_imu_x = current_velocity_x;current_velocity_imu_y = current_velocity_y;current_velocity_imu_z = current_velocity_z;current_pose_odom.x = current_pose.x;current_pose_odom.y = current_pose.y;current_pose_odom.z = current_pose.z;current_pose_odom.roll = current_pose.roll;current_pose_odom.pitch = current_pose.pitch;current_pose_odom.yaw = current_pose.yaw;current_pose_imu_odom.x = current_pose.x;current_pose_imu_odom.y = current_pose.y;current_pose_imu_odom.z = current_pose.z;current_pose_imu_odom.roll = current_pose.roll;current_pose_imu_odom.pitch = current_pose.pitch;current_pose_imu_odom.yaw = current_pose.yaw;//当前速度平滑值 = (当前速度+上一时间速度+上上一时间速度)/3.0current_velocity_smooth = (current_velocity + previous_velocity + previous_previous_velocity) / 3.0;if (current_velocity_smooth < 0.2){current_velocity_smooth = 0.0;}//当前加速度 = (当前速度 - 上一时刻速度)/时间间隔current_accel = (diff_time > 0) ? ((current_velocity - previous_velocity) / diff_time) : 0;current_accel_x = (diff_time > 0) ? ((current_velocity_x - previous_velocity_x) / diff_time) : 0;current_accel_y = (diff_time > 0) ? ((current_velocity_y - previous_velocity_y) / diff_time) : 0;current_accel_z = (diff_time > 0) ? ((current_velocity_z - previous_velocity_z) / diff_time) : 0;//估计速度m/s,km/hestimated_vel_mps.data = current_velocity;estimated_vel_kmph.data = current_velocity * 3.6;estimated_vel_mps_pub.publish(estimated_vel_mps);estimated_vel_kmph_pub.publish(estimated_vel_kmph);// Set values for publishing pose//速度积分预估值的姿态predict_q.setRPY(predict_pose.roll, predict_pose.pitch, predict_pose.yaw);if (_use_local_transform == true){tf::Vector3 v(predict_pose.x, predict_pose.y, predict_pose.z);tf::Transform transform(predict_q, v);predict_pose_msg.header.frame_id = "/map";predict_pose_msg.header.stamp = current_scan_time;predict_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX();predict_pose_msg.pose.position.y = (local_transform * transform).getOrigin().getY();predict_pose_msg.pose.position.z = (local_transform * transform).getOrigin().getZ();predict_pose_msg.pose.orientation.x = (local_transform * transform).getRotation().x();predict_pose_msg.pose.orientation.y = (local_transform * transform).getRotation().y();predict_pose_msg.pose.orientation.z = (local_transform * transform).getRotation().z();predict_pose_msg.pose.orientation.w = (local_transform * transform).getRotation().w();}else //默认为false{predict_pose_msg.header.frame_id = "/map";predict_pose_msg.header.stamp = current_scan_time;predict_pose_msg.pose.position.x = predict_pose.x;predict_pose_msg.pose.position.y = predict_pose.y;predict_pose_msg.pose.position.z = predict_pose.z;predict_pose_msg.pose.orientation.x = predict_q.x();predict_pose_msg.pose.orientation.y = predict_q.y();predict_pose_msg.pose.orientation.z = predict_q.z();predict_pose_msg.pose.orientation.w = predict_q.w();}tf::Quaternion predict_q_imu;predict_q_imu.setRPY(predict_pose_imu.roll, predict_pose_imu.pitch, predict_pose_imu.yaw);predict_pose_imu_msg.header.frame_id = "map";predict_pose_imu_msg.header.stamp = input->header.stamp;predict_pose_imu_msg.pose.position.x = predict_pose_imu.x;predict_pose_imu_msg.pose.position.y = predict_pose_imu.y;predict_pose_imu_msg.pose.position.z = predict_pose_imu.z;predict_pose_imu_msg.pose.orientation.x = predict_q_imu.x();predict_pose_imu_msg.pose.orientation.y = predict_q_imu.y();predict_pose_imu_msg.pose.orientation.z = predict_q_imu.z();predict_pose_imu_msg.pose.orientation.w = predict_q_imu.w();predict_pose_imu_pub.publish(predict_pose_imu_msg);tf::Quaternion predict_q_odom;predict_q_odom.setRPY(predict_pose_odom.roll, predict_pose_odom.pitch, predict_pose_odom.yaw);predict_pose_odom_msg.header.frame_id = "map";predict_pose_odom_msg.header.stamp = input->header.stamp;predict_pose_odom_msg.pose.position.x = predict_pose_odom.x;predict_pose_odom_msg.pose.position.y = predict_pose_odom.y;predict_pose_odom_msg.pose.position.z = predict_pose_odom.z;predict_pose_odom_msg.pose.orientation.x = predict_q_odom.x();predict_pose_odom_msg.pose.orientation.y = predict_q_odom.y();predict_pose_odom_msg.pose.orientation.z = predict_q_odom.z();predict_pose_odom_msg.pose.orientation.w = predict_q_odom.w();predict_pose_odom_pub.publish(predict_pose_odom_msg);tf::Quaternion predict_q_imu_odom;predict_q_imu_odom.setRPY(predict_pose_imu_odom.roll, predict_pose_imu_odom.pitch, predict_pose_imu_odom.yaw);predict_pose_imu_odom_msg.header.frame_id = "map";predict_pose_imu_odom_msg.header.stamp = input->header.stamp;predict_pose_imu_odom_msg.pose.position.x = predict_pose_imu_odom.x;predict_pose_imu_odom_msg.pose.position.y = predict_pose_imu_odom.y;predict_pose_imu_odom_msg.pose.position.z = predict_pose_imu_odom.z;predict_pose_imu_odom_msg.pose.orientation.x = predict_q_imu_odom.x();predict_pose_imu_odom_msg.pose.orientation.y = predict_q_imu_odom.y();predict_pose_imu_odom_msg.pose.orientation.z = predict_q_imu_odom.z();predict_pose_imu_odom_msg.pose.orientation.w = predict_q_imu_odom.w();predict_pose_imu_odom_pub.publish(predict_pose_imu_odom_msg);//ndt_pose 计算出来的当前位置信息ndt_q.setRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw);if (_use_local_transform == true){tf::Vector3 v(ndt_pose.x, ndt_pose.y, ndt_pose.z);tf::Transform transform(ndt_q, v);ndt_pose_msg.header.frame_id = "/map";ndt_pose_msg.header.stamp = current_scan_time;ndt_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX();ndt_pose_msg.pose.position.y = (local_transform * transform).getOrigin().getY();ndt_pose_msg.pose.position.z = (local_transform * transform).getOrigin().getZ();ndt_pose_msg.pose.orientation.x = (local_transform * transform).getRotation().x();ndt_pose_msg.pose.orientation.y = (local_transform * transform).getRotation().y();ndt_pose_msg.pose.orientation.z = (local_transform * transform).getRotation().z();ndt_pose_msg.pose.orientation.w = (local_transform * transform).getRotation().w();}else //默认值{ndt_pose_msg.header.frame_id = "/map";ndt_pose_msg.header.stamp = current_scan_time;ndt_pose_msg.pose.position.x = ndt_pose.x;ndt_pose_msg.pose.position.y = ndt_pose.y;ndt_pose_msg.pose.position.z = ndt_pose.z;ndt_pose_msg.pose.orientation.x = ndt_q.x();ndt_pose_msg.pose.orientation.y = ndt_q.y();ndt_pose_msg.pose.orientation.z = ndt_q.z();ndt_pose_msg.pose.orientation.w = ndt_q.w();}//current_pose 当前判断出来的位置,排除了异常匹配的更精准的位置current_q.setRPY(current_pose.roll, current_pose.pitch, current_pose.yaw);// current_pose is published by vel_pose_mux/*current_pose_msg.header.frame_id = "/map";current_pose_msg.header.stamp = current_scan_time;current_pose_msg.pose.position.x = current_pose.x;current_pose_msg.pose.position.y = current_pose.y;current_pose_msg.pose.position.z = current_pose.z;current_pose_msg.pose.orientation.x = current_q.x();current_pose_msg.pose.orientation.y = current_q.y();current_pose_msg.pose.orientation.z = current_q.z();current_pose_msg.pose.orientation.w = current_q.w();*///localizer_pose 当前雷达的位置localizer_q.setRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw);if (_use_local_transform == true){tf::Vector3 v(localizer_pose.x, localizer_pose.y, localizer_pose.z);tf::Transform transform(localizer_q, v);localizer_pose_msg.header.frame_id = "/map";localizer_pose_msg.header.stamp = current_scan_time;localizer_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX();localizer_pose_msg.pose.position.y = (local_transform * transform).getOrigin().getY();localizer_pose_msg.pose.position.z = (local_transform * transform).getOrigin().getZ();localizer_pose_msg.pose.orientation.x = (local_transform * transform).getRotation().x();localizer_pose_msg.pose.orientation.y = (local_transform * transform).getRotation().y();localizer_pose_msg.pose.orientation.z = (local_transform * transform).getRotation().z();localizer_pose_msg.pose.orientation.w = (local_transform * transform).getRotation().w();}else{localizer_pose_msg.header.frame_id = "/map";localizer_pose_msg.header.stamp = current_scan_time;localizer_pose_msg.pose.position.x = localizer_pose.x;localizer_pose_msg.pose.position.y = localizer_pose.y;localizer_pose_msg.pose.position.z = localizer_pose.z;localizer_pose_msg.pose.orientation.x = localizer_q.x();localizer_pose_msg.pose.orientation.y = localizer_q.y();localizer_pose_msg.pose.orientation.z = localizer_q.z();localizer_pose_msg.pose.orientation.w = localizer_q.w();}predict_pose_pub.publish(predict_pose_msg);ndt_pose_pub.publish(ndt_pose_msg);// current_pose is published by vel_pose_mux//    current_pose_pub.publish(current_pose_msg);localizer_pose_pub.publish(localizer_pose_msg);// Send TF "/base_link" to "/map"// base_link到map原点的tf变换transform.setOrigin(tf::Vector3(current_pose.x, current_pose.y, current_pose.z));transform.setRotation(current_q);//    br.sendTransform(tf::StampedTransform(transform, current_scan_time, "/map", "/base_footprint"));if (_use_local_transform == true){br.sendTransform(tf::StampedTransform(local_transform * transform, current_scan_time, "/map", "/base_footprint"));}else{//发步tf变换br.sendTransform(tf::StampedTransform(transform, current_scan_time, "/map", "/base_footprint"));}//计算匹配所需要的时间matching_end = std::chrono::system_clock::now();exe_time = std::chrono::duration_cast<std::chrono::microseconds>(matching_end - matching_start).count() / 1000.0;time_ndt_matching.data = exe_time;time_ndt_matching_pub.publish(time_ndt_matching);// Set values for /estimate_twist//发布底盘的运动速度estimate_twist_msg.header.stamp = current_scan_time;estimate_twist_msg.header.frame_id = "/base_link";estimate_twist_msg.twist.linear.x = current_velocity;estimate_twist_msg.twist.linear.y = 0.0;estimate_twist_msg.twist.linear.z = 0.0;estimate_twist_msg.twist.angular.x = 0.0;estimate_twist_msg.twist.angular.y = 0.0;estimate_twist_msg.twist.angular.z = angular_velocity;estimate_twist_pub.publish(estimate_twist_msg);geometry_msgs::Vector3Stamped estimate_vel_msg;estimate_vel_msg.header.stamp = current_scan_time;estimate_vel_msg.vector.x = current_velocity;estimated_vel_pub.publish(estimate_vel_msg);// Set values for /ndt_stat//发布这次匹配的中的数据值ndt_stat_msg.header.stamp = current_scan_time;//当前雷达的时间戳ndt_stat_msg.exe_time = time_ndt_matching.data;//此次匹配所花时间ndt_stat_msg.iteration = iteration;//迭代次数ndt_stat_msg.score = fitness_score;//匹配分数ndt_stat_msg.velocity = current_velocity;//当前速度ndt_stat_msg.acceleration = current_accel;//当前加速度ndt_stat_msg.use_predict_pose = 0;//匹配的数据与上次数据的差异值是否过大ndt_stat_pub.publish(ndt_stat_msg);/* Compute NDT_Reliability *///此次ndt匹配的可靠性ndt_reliability.data = Wa * (exe_time / 100.0) * 100.0 + Wb * (iteration / 10.0) * 100.0 +Wc * ((2.0 - trans_probability) / 2.0) * 100.0;ndt_reliability_pub.publish(ndt_reliability);// Write log//ndt日志if(_output_log_data){if (!ofs){std::cerr << "Could not open " << filename << "." << std::endl;}else{ofs << input->header.seq << "," << scan_points_num << "," << step_size << "," << trans_eps << "," << std::fixed<< std::setprecision(5) << current_pose.x << "," << std::fixed << std::setprecision(5) << current_pose.y << ","<< std::fixed << std::setprecision(5) << current_pose.z << "," << current_pose.roll << "," << current_pose.pitch<< "," << current_pose.yaw << "," << predict_pose.x << "," << predict_pose.y << "," << predict_pose.z << ","<< predict_pose.roll << "," << predict_pose.pitch << "," << predict_pose.yaw << ","<< current_pose.x - predict_pose.x << "," << current_pose.y - predict_pose.y << ","<< current_pose.z - predict_pose.z << "," << current_pose.roll - predict_pose.roll << ","<< current_pose.pitch - predict_pose.pitch << "," << current_pose.yaw - predict_pose.yaw << ","<< predict_pose_error << "," << iteration << "," << fitness_score << "," << trans_probability << ","<< ndt_reliability.data << "," << current_velocity << "," << current_velocity_smooth << "," << current_accel<< "," << angular_velocity << "," << time_ndt_matching.data << "," << align_time << "," << getFitnessScore_time<< std::endl;}}std::cout << "-----------------------------------------------------------------" << std::endl;std::cout << "Sequence: " << input->header.seq << std::endl;std::cout << "Timestamp: " << input->header.stamp << std::endl;std::cout << "Frame ID: " << input->header.frame_id << std::endl;//		std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl;std::cout << "Number of Filtered Scan Points: " << scan_points_num << " points." << std::endl;std::cout << "NDT has converged: " << has_converged << std::endl;std::cout << "Fitness Score: " << fitness_score << std::endl;std::cout << "Transformation Probability: " << trans_probability << std::endl;std::cout << "Execution Time: " << exe_time << " ms." << std::endl;std::cout << "Number of Iterations: " << iteration << std::endl;std::cout << "NDT Reliability: " << ndt_reliability.data << std::endl;std::cout << "(x,y,z,roll,pitch,yaw): " << std::endl;std::cout << "(" << current_pose.x << ", " << current_pose.y << ", " << current_pose.z << ", " << current_pose.roll<< ", " << current_pose.pitch << ", " << current_pose.yaw << ")" << std::endl;std::cout << "Transformation Matrix: " << std::endl;std::cout << t << std::endl;std::cout << "Align time: " << align_time << std::endl;std::cout << "Get fitness score time: " << getFitnessScore_time << std::endl;std::cout << "-----------------------------------------------------------------" << std::endl;offset_imu_x = 0.0;offset_imu_y = 0.0;offset_imu_z = 0.0;offset_imu_roll = 0.0;offset_imu_pitch = 0.0;offset_imu_yaw = 0.0;offset_odom_x = 0.0;offset_odom_y = 0.0;offset_odom_z = 0.0;offset_odom_roll = 0.0;offset_odom_pitch = 0.0;offset_odom_yaw = 0.0;offset_imu_odom_x = 0.0;offset_imu_odom_y = 0.0;offset_imu_odom_z = 0.0;offset_imu_odom_roll = 0.0;offset_imu_odom_pitch = 0.0;offset_imu_odom_yaw = 0.0;// Update previous_***//更新上一时刻数据值previous_pose.x = current_pose.x;previous_pose.y = current_pose.y;previous_pose.z = current_pose.z;previous_pose.roll = current_pose.roll;previous_pose.pitch = current_pose.pitch;previous_pose.yaw = current_pose.yaw;previous_scan_time = current_scan_time;previous_previous_velocity = previous_velocity;previous_velocity = current_velocity;previous_velocity_x = current_velocity_x;previous_velocity_y = current_velocity_y;previous_velocity_z = current_velocity_z;previous_accel = current_accel;previous_estimated_vel_kmph.data = estimated_vel_kmph.data;}
}

开启额外的线程进行更新地图

/void* thread_func(void* args)
{ros::NodeHandle nh_map;ros::CallbackQueue map_callback_queue;nh_map.setCallbackQueue(&map_callback_queue);ros::Subscriber map_sub = nh_map.subscribe("points_map", 10, map_callback);ros::Rate ros_rate(10);while (nh_map.ok()){map_callback_queue.callAvailable(ros::WallDuration());ros_rate.sleep();}

目前对于ndt定位的理解还是比较晦涩,下一步打算从autoware高精度建图开始学习。

查看全文
如若内容造成侵权/违法违规/事实不符,请联系编程学习网邮箱:809451989@qq.com进行投诉反馈,一经查实,立即删除!

相关文章

  1. Atcoder - 091C 扫描线 and Atcoder - 062D 优先队列 + 前后缀和

    <Atcoder - 091C> 扫描线https://atcoder.jp/contests/abc091/tasks/arc092_a题意:有n个红点,n个蓝点,所选的红点和蓝点能够成友好的条件是:红点的横纵坐标分别小于蓝点的横纵坐标。取过的点不能重复取,问最多能构成几对友好。思路:定义结构体,将所有红点蓝点统一…...

    2024/5/5 21:18:39
  2. 计算机 黑客攻击

    黑客的动机 01 好奇好玩 02 网络犯罪 03 黑客行动主义者, 影响社会 或 达到政治目的 手段 01 不使用技术, 而是欺骗别人, 让别人泄密, 这个是 社会工程学. 或者让别人配置电脑使其变得易于攻击 钓鱼网站: 仿制官网, 实际是把信息给了黑客 假托: 冒充 IT等相关人员给你打电话…...

    2024/5/5 20:29:59
  3. SpringBoot:快速入门

    什么是SpringSpring是一个开源框架,2003 年兴起的一个轻量级的Java 开发框架,作者:Rod Johnson 。Spring是为了解决企业级应用开发的复杂性而创建的,简化开发。 Spring是如何简化Java开发的为了降低Java开发的复杂性,Spring采用了以下4种关键策略:基于POJO的轻量级和最小…...

    2024/4/23 14:15:36
  4. LINUX从零开始——ENGINEER(云计算应用管理)——Day4-1 [配置Linux网络 、源码编译安装、自定义Yum仓库、日志管理]

    一、环境准备 1.建议还原快照,开启CentOS7虚拟机,以root用户登录 课前回顾: 1.交换空间的作用? 缓解内存的压力 2.格式化交换文件系统的命令? mkswap 3.查看内存空间以及交换空间的命令? free 4.利用dd命令生成2G的文件如何操作? dd if=/dev/zero of=/opt/1.txt bs=…...

    2024/5/6 1:26:09
  5. AI三大主义:符号主义、联结主义、行为主义

    一、符号主义(symbolicism) 符号主义(symbolicism)=逻辑主义(Logicism)=心理学派(Psychlogism)=计算机学派(Computerism),其原理主要为物理符号系统(即符号操作系统)假设和有限合理性原理。 早期的人工智能研究者绝大多数属于此类。 主要观点:人类认知和思维的基本单元是符…...

    2024/4/23 14:15:27
  6. 消息队列RocketMQ

    目录一. 简介二. 单节点RocketMQ安装2.1 环境准备2.2 安装配置三. 概念模型三. 生产者与消费者3.1 生产者代码实现3.2 消费者代码实现3.3 RocketMQ顺序消息发送3.4 事务性消息3.4.1 概述3.4.2 事务性生产者代码实现3.4.3 事务性消费者代码实现 一. 简介 MQ全称Message Queue,消…...

    2024/4/23 14:15:33
  7. LINUX从零开始——ENGINEER(云计算应用管理)——Day4-2 [配置Linux网络 、源码编译安装、自定义Yum仓库、日志管理]

    一、环境准备 1.开启两台虚拟机,以root用户登录 课程回顾: 1.查看系统进程信息有哪些命令? pstree ps aux ps -elf 2.如何查看占用内存最高的进程? top 3.永久设置主机名配置文件路径? /etc/hostname 4.设置开机自动挂载配置文件路径? /etc/fstab 5.yum客户端配置…...

    2024/5/5 18:47:45
  8. 面试题整理

    目录一、HashMap和CocurrentHashMap说一下你对HashMap的理解;他的底层结构是什么样的;一个数据是怎么存到,map里面的;怎么可以让HashMap的碰撞变小;为什么不能用可变类型做键值呢;链表什么时候转成红黑树;为什么要转成红黑树;红黑树是什么样的,他的结构是什么样的;他…...

    2024/5/6 0:29:45
  9. 第一次面试准备

    我呢最近这一周都在找实习找工作,在周三周四时候投递了很多简历,估计收到的疫情的影响,目前只收到一家公司的面试邀请。我真的 好像去实习呀,好像去实习呀!为了准备好实习,这两天临时集中突击一下,面试题。。。。。祝我好运!!! 面试复习第一弹: 1:什么是同步逻辑什…...

    2024/5/5 19:50:38
  10. 使用matplotlib在一张图上画多条曲线

    做数据分析,还有机器学习的收敛性,准确性分析时,往往需要将一些数据图形化,以曲线的形式显示出来,下面就介绍两种方式来实现这个小问题,一种是object-oriented面向对象的,另一种是基于plt的。下面这个方式是面向对象的方式:import numpy as np import matplotlib.pyplo…...

    2024/4/27 19:07:15
  11. python基础编程:关于python中plt.hist参数的使用详解

    今天小编就为大家分享一篇关于python中plt.hist参数的使用详解,具有很好的参考价值,希望对大家有所帮助。一起跟随小编过来看看吧 如下所示: matplotlib.pyplot.hist( x, bins=10, range=None, normed=False, weights=None, cumulative=False, bottom=None, histtype=ubar…...

    2024/5/6 1:22:22
  12. python基础教程:在Python下利用OpenCV来旋转图像的教程

    这篇文章主要介绍了在Python下利用OpenCV来旋转图像的教程,代码和核心的算法都非常简单,需要的朋友可以参考下 OpenCV是应用最被广泛的的开源视觉库。他允许你使用很少的代码来检测图片或视频中的人脸。 这里有一些互联网上的教程来阐述怎么在OpenCV中使用仿射变换(affine tra…...

    2024/5/5 17:17:18
  13. python基础教程:python、PyTorch图像读取与numpy转换实例

    今天小编就为大家分享一篇python、PyTorch图像读取与numpy转换实例,具有很好的参考价值,希望对大家有所帮助。一起跟随小编过来看看吧 Tensor转为numpy np.array(Tensor) numpy转换为Tensor torch.Tensor(numpy.darray) PIL.Image.Image转换成numpy np.array(PIL.Image.Image…...

    2024/4/17 8:30:59
  14. 一个用于嵌入式开发的简单可靠的消息系统-STOpen消息系统

    在一般中低端的嵌入式系统里面,程序要么是跑大循环,要么是跑一个简单的操作系统(比如ucos,rtthread,freertos等等),简单和效率是第一要素,毕竟系统硬件资源有限。 要在这方寸之间,施展十八般武艺,实属具有一定的挑战性。 我们实现了一个简单的类windows的消息系统,让…...

    2024/5/5 21:45:55
  15. python基础编程:Python中turtle作图示例

    这篇文章主要介绍了Python中turtle作图示例,分享了几则turtle作图的小实例,具有一定参考价值,需要的朋友可以了解下 在Python里,海龟不仅可以画简单的黑线,还可以用它画更复杂的几何图形,用不同的颜色,甚至还可以给形状填色。 一、从基本的正方形开始 引入turtle模块并创…...

    2024/4/17 8:30:29
  16. python基础教程:从局部变量和全局变量开始全面解析Python中变量的作用域

    无论是以类为基础的面相对象编程,还是单纯函数内部变量的定义,变量的作用域始终是Python学习中一个必须理解掌握的环节,下面我们从局部变量和全局变量开始全面解析Python中变量的作用域,需要的朋友可以参考下 理解全局变量和局部变量 1.定义的函数内部的变量名如果是第一次出现…...

    2024/5/6 1:52:10
  17. 大数据与云计算之间的关系是怎样的?

    如今,两种主流技术已成为IT领域关注的焦点-大数据和云计算。根本不同的是,大数据只涉及处理海量数据,而云计算则涉及基础架构。但是,大数据和云技术提供的简化功能是其被大量企业采用的主要原因。例如,亚马逊的“ Elastic Map Reduce”演示了如何利用Cloud Elastic Comput…...

    2024/5/5 21:53:45
  18. 您应该知道的101个大数据术语

    由于每天都会产生大量的数据,因此了解大数据的复杂性变得至关重要。如果您打算进入大数据星球,则应该熟悉大数据术语。这些术语将帮助您深入了解大数据世界。因此,让我们从术语大数据本身开始-由于业务专业人员,项目,从业人员和供应商以不同的方式来理解“大数据”,因此很…...

    2024/4/23 14:15:25
  19. BFS/DFS基本代码实现

    今日初学,帮助理解 bfs基本代码 #include<stdio.h> #include<iostream> #include<queue> using namespace std; int dri4[4][2]= {{-1,0},{1,0},{0,-1},{0,1}};struct node {int i,j;//坐标int t;//遍历个数 };int vis[105][105];//标记数组(是否遍历) int …...

    2024/4/23 14:15:21
  20. python中文分词教程之前向最大正向匹配算法详解

    中文分词是中文文本处理的一个基础性工作,然而长久以来,在Python编程领域,一直缺少高准确率、高效率的分词组件。下面这篇文章主要给大家介绍了关于python中文分词教程之前向最大正向匹配算法的相关资料,需要的朋友可以参考下。 前言 大家都知道,英文的分词由于单词间是以…...

    2024/4/23 14:15:23

最新文章

  1. 记录PR学习查漏补缺(持续补充中。。。)

    记录PR学习查漏补缺 常用快捷键文件编辑素材序列标记字幕窗口帮助 效果基本3D高斯模糊查找边缘色彩颜色平衡超级键马赛克中间值变形稳定器轨道遮罩键 常用 快捷键 注意&#xff1a;比较常用的用红色字体显示 文件 快捷键作用Ctrl Alt N新建项目Ctrl O打开项目Ctrl I导入…...

    2024/5/6 3:32:56
  2. 梯度消失和梯度爆炸的一些处理方法

    在这里是记录一下梯度消失或梯度爆炸的一些处理技巧。全当学习总结了如有错误还请留言&#xff0c;在此感激不尽。 权重和梯度的更新公式如下&#xff1a; w w − η ⋅ ∇ w w w - \eta \cdot \nabla w ww−η⋅∇w 个人通俗的理解梯度消失就是网络模型在反向求导的时候出…...

    2024/3/20 10:50:27
  3. 同一个pdf在windows和linux中的页数不一样

    之前认为PDF的格式&#xff0c;至少页数是不会变化的&#xff0c;结果最近发现一个文档在windows和linux中的页数不一样&#xff0c;linux中的pdf进入像word一样排版变得紧凑了&#xff0c;原本在下一页的几行进入了上一页的末尾。问了gpt后得到这样的回答&#xff1a; PDF文档…...

    2024/5/5 6:48:14
  4. Linux mount用法

    在Linux系统中&#xff0c;系统自动挂载了以下挂载点&#xff1a; /: xfs文件系统&#xff0c;根文件系统, 所有其他文件系统的挂载点。 /sys: sysfs文件系统&#xff0c;提供内核对象的信息和接口。 /proc: proc文件系统&#xff0c;提供进程和系统信息。 /dev: devtmpfs文件系…...

    2024/5/5 8:38:45
  5. 【外汇早评】美通胀数据走低,美元调整

    原标题:【外汇早评】美通胀数据走低,美元调整昨日美国方面公布了新一期的核心PCE物价指数数据,同比增长1.6%,低于前值和预期值的1.7%,距离美联储的通胀目标2%继续走低,通胀压力较低,且此前美国一季度GDP初值中的消费部分下滑明显,因此市场对美联储后续更可能降息的政策…...

    2024/5/4 23:54:56
  6. 【原油贵金属周评】原油多头拥挤,价格调整

    原标题:【原油贵金属周评】原油多头拥挤,价格调整本周国际劳动节,我们喜迎四天假期,但是整个金融市场确实流动性充沛,大事频发,各个商品波动剧烈。美国方面,在本周四凌晨公布5月份的利率决议和新闻发布会,维持联邦基金利率在2.25%-2.50%不变,符合市场预期。同时美联储…...

    2024/5/4 23:54:56
  7. 【外汇周评】靓丽非农不及疲软通胀影响

    原标题:【外汇周评】靓丽非农不及疲软通胀影响在刚结束的周五,美国方面公布了新一期的非农就业数据,大幅好于前值和预期,新增就业重新回到20万以上。具体数据: 美国4月非农就业人口变动 26.3万人,预期 19万人,前值 19.6万人。 美国4月失业率 3.6%,预期 3.8%,前值 3…...

    2024/5/4 23:54:56
  8. 【原油贵金属早评】库存继续增加,油价收跌

    原标题:【原油贵金属早评】库存继续增加,油价收跌周三清晨公布美国当周API原油库存数据,上周原油库存增加281万桶至4.692亿桶,增幅超过预期的74.4万桶。且有消息人士称,沙特阿美据悉将于6月向亚洲炼油厂额外出售更多原油,印度炼油商预计将每日获得至多20万桶的额外原油供…...

    2024/5/4 23:55:17
  9. 【外汇早评】日本央行会议纪要不改日元强势

    原标题:【外汇早评】日本央行会议纪要不改日元强势近两日日元大幅走强与近期市场风险情绪上升,避险资金回流日元有关,也与前一段时间的美日贸易谈判给日本缓冲期,日本方面对汇率问题也避免继续贬值有关。虽然今日早间日本央行公布的利率会议纪要仍然是支持宽松政策,但这符…...

    2024/5/4 23:54:56
  10. 【原油贵金属早评】欧佩克稳定市场,填补伊朗问题的影响

    原标题:【原油贵金属早评】欧佩克稳定市场,填补伊朗问题的影响近日伊朗局势升温,导致市场担忧影响原油供给,油价试图反弹。此时OPEC表态稳定市场。据消息人士透露,沙特6月石油出口料将低于700万桶/日,沙特已经收到石油消费国提出的6月份扩大出口的“适度要求”,沙特将满…...

    2024/5/4 23:55:05
  11. 【外汇早评】美欲与伊朗重谈协议

    原标题:【外汇早评】美欲与伊朗重谈协议美国对伊朗的制裁遭到伊朗的抗议,昨日伊朗方面提出将部分退出伊核协议。而此行为又遭到欧洲方面对伊朗的谴责和警告,伊朗外长昨日回应称,欧洲国家履行它们的义务,伊核协议就能保证存续。据传闻伊朗的导弹已经对准了以色列和美国的航…...

    2024/5/4 23:54:56
  12. 【原油贵金属早评】波动率飙升,市场情绪动荡

    原标题:【原油贵金属早评】波动率飙升,市场情绪动荡因中美贸易谈判不安情绪影响,金融市场各资产品种出现明显的波动。随着美国与中方开启第十一轮谈判之际,美国按照既定计划向中国2000亿商品征收25%的关税,市场情绪有所平复,已经开始接受这一事实。虽然波动率-恐慌指数VI…...

    2024/5/4 23:55:16
  13. 【原油贵金属周评】伊朗局势升温,黄金多头跃跃欲试

    原标题:【原油贵金属周评】伊朗局势升温,黄金多头跃跃欲试美国和伊朗的局势继续升温,市场风险情绪上升,避险黄金有向上突破阻力的迹象。原油方面稍显平稳,近期美国和OPEC加大供给及市场需求回落的影响,伊朗局势并未推升油价走强。近期中美贸易谈判摩擦再度升级,美国对中…...

    2024/5/4 23:54:56
  14. 【原油贵金属早评】市场情绪继续恶化,黄金上破

    原标题:【原油贵金属早评】市场情绪继续恶化,黄金上破周初中国针对于美国加征关税的进行的反制措施引发市场情绪的大幅波动,人民币汇率出现大幅的贬值动能,金融市场受到非常明显的冲击。尤其是波动率起来之后,对于股市的表现尤其不安。隔夜美国股市出现明显的下行走势,这…...

    2024/5/6 1:40:42
  15. 【外汇早评】美伊僵持,风险情绪继续升温

    原标题:【外汇早评】美伊僵持,风险情绪继续升温昨日沙特两艘油轮再次发生爆炸事件,导致波斯湾局势进一步恶化,市场担忧美伊可能会出现摩擦生火,避险品种获得支撑,黄金和日元大幅走强。美指受中美贸易问题影响而在低位震荡。继5月12日,四艘商船在阿联酋领海附近的阿曼湾、…...

    2024/5/4 23:54:56
  16. 【原油贵金属早评】贸易冲突导致需求低迷,油价弱势

    原标题:【原油贵金属早评】贸易冲突导致需求低迷,油价弱势近日虽然伊朗局势升温,中东地区几起油船被袭击事件影响,但油价并未走高,而是出于调整结构中。由于市场预期局势失控的可能性较低,而中美贸易问题导致的全球经济衰退风险更大,需求会持续低迷,因此油价调整压力较…...

    2024/5/4 23:55:17
  17. 氧生福地 玩美北湖(上)——为时光守候两千年

    原标题:氧生福地 玩美北湖(上)——为时光守候两千年一次说走就走的旅行,只有一张高铁票的距离~ 所以,湖南郴州,我来了~ 从广州南站出发,一个半小时就到达郴州西站了。在动车上,同时改票的南风兄和我居然被分到了一个车厢,所以一路非常愉快地聊了过来。 挺好,最起…...

    2024/5/4 23:55:06
  18. 氧生福地 玩美北湖(中)——永春梯田里的美与鲜

    原标题:氧生福地 玩美北湖(中)——永春梯田里的美与鲜一觉醒来,因为大家太爱“美”照,在柳毅山庄去寻找龙女而错过了早餐时间。近十点,向导坏坏还是带着饥肠辘辘的我们去吃郴州最富有盛名的“鱼头粉”。说这是“十二分推荐”,到郴州必吃的美食之一。 哇塞!那个味美香甜…...

    2024/5/4 23:54:56
  19. 氧生福地 玩美北湖(下)——奔跑吧骚年!

    原标题:氧生福地 玩美北湖(下)——奔跑吧骚年!让我们红尘做伴 活得潇潇洒洒 策马奔腾共享人世繁华 对酒当歌唱出心中喜悦 轰轰烈烈把握青春年华 让我们红尘做伴 活得潇潇洒洒 策马奔腾共享人世繁华 对酒当歌唱出心中喜悦 轰轰烈烈把握青春年华 啊……啊……啊 两…...

    2024/5/4 23:55:06
  20. 扒开伪装医用面膜,翻六倍价格宰客,小姐姐注意了!

    原标题:扒开伪装医用面膜,翻六倍价格宰客,小姐姐注意了!扒开伪装医用面膜,翻六倍价格宰客!当行业里的某一品项火爆了,就会有很多商家蹭热度,装逼忽悠,最近火爆朋友圈的医用面膜,被沾上了污点,到底怎么回事呢? “比普通面膜安全、效果好!痘痘、痘印、敏感肌都能用…...

    2024/5/5 8:13:33
  21. 「发现」铁皮石斛仙草之神奇功效用于医用面膜

    原标题:「发现」铁皮石斛仙草之神奇功效用于医用面膜丽彦妆铁皮石斛医用面膜|石斛多糖无菌修护补水贴19大优势: 1、铁皮石斛:自唐宋以来,一直被列为皇室贡品,铁皮石斛生于海拔1600米的悬崖峭壁之上,繁殖力差,产量极低,所以古代仅供皇室、贵族享用 2、铁皮石斛自古民间…...

    2024/5/4 23:55:16
  22. 丽彦妆\医用面膜\冷敷贴轻奢医学护肤引导者

    原标题:丽彦妆\医用面膜\冷敷贴轻奢医学护肤引导者【公司简介】 广州华彬企业隶属香港华彬集团有限公司,专注美业21年,其旗下品牌: 「圣茵美」私密荷尔蒙抗衰,产后修复 「圣仪轩」私密荷尔蒙抗衰,产后修复 「花茵莳」私密荷尔蒙抗衰,产后修复 「丽彦妆」专注医学护…...

    2024/5/4 23:54:58
  23. 广州械字号面膜生产厂家OEM/ODM4项须知!

    原标题:广州械字号面膜生产厂家OEM/ODM4项须知!广州械字号面膜生产厂家OEM/ODM流程及注意事项解读: 械字号医用面膜,其实在我国并没有严格的定义,通常我们说的医美面膜指的应该是一种「医用敷料」,也就是说,医用面膜其实算作「医疗器械」的一种,又称「医用冷敷贴」。 …...

    2024/5/4 23:55:01
  24. 械字号医用眼膜缓解用眼过度到底有无作用?

    原标题:械字号医用眼膜缓解用眼过度到底有无作用?医用眼膜/械字号眼膜/医用冷敷眼贴 凝胶层为亲水高分子材料,含70%以上的水分。体表皮肤温度传导到本产品的凝胶层,热量被凝胶内水分子吸收,通过水分的蒸发带走大量的热量,可迅速地降低体表皮肤局部温度,减轻局部皮肤的灼…...

    2024/5/4 23:54:56
  25. 配置失败还原请勿关闭计算机,电脑开机屏幕上面显示,配置失败还原更改 请勿关闭计算机 开不了机 这个问题怎么办...

    解析如下&#xff1a;1、长按电脑电源键直至关机&#xff0c;然后再按一次电源健重启电脑&#xff0c;按F8健进入安全模式2、安全模式下进入Windows系统桌面后&#xff0c;按住“winR”打开运行窗口&#xff0c;输入“services.msc”打开服务设置3、在服务界面&#xff0c;选中…...

    2022/11/19 21:17:18
  26. 错误使用 reshape要执行 RESHAPE,请勿更改元素数目。

    %读入6幅图像&#xff08;每一幅图像的大小是564*564&#xff09; f1 imread(WashingtonDC_Band1_564.tif); subplot(3,2,1),imshow(f1); f2 imread(WashingtonDC_Band2_564.tif); subplot(3,2,2),imshow(f2); f3 imread(WashingtonDC_Band3_564.tif); subplot(3,2,3),imsho…...

    2022/11/19 21:17:16
  27. 配置 已完成 请勿关闭计算机,win7系统关机提示“配置Windows Update已完成30%请勿关闭计算机...

    win7系统关机提示“配置Windows Update已完成30%请勿关闭计算机”问题的解决方法在win7系统关机时如果有升级系统的或者其他需要会直接进入一个 等待界面&#xff0c;在等待界面中我们需要等待操作结束才能关机&#xff0c;虽然这比较麻烦&#xff0c;但是对系统进行配置和升级…...

    2022/11/19 21:17:15
  28. 台式电脑显示配置100%请勿关闭计算机,“准备配置windows 请勿关闭计算机”的解决方法...

    有不少用户在重装Win7系统或更新系统后会遇到“准备配置windows&#xff0c;请勿关闭计算机”的提示&#xff0c;要过很久才能进入系统&#xff0c;有的用户甚至几个小时也无法进入&#xff0c;下面就教大家这个问题的解决方法。第一种方法&#xff1a;我们首先在左下角的“开始…...

    2022/11/19 21:17:14
  29. win7 正在配置 请勿关闭计算机,怎么办Win7开机显示正在配置Windows Update请勿关机...

    置信有很多用户都跟小编一样遇到过这样的问题&#xff0c;电脑时发现开机屏幕显现“正在配置Windows Update&#xff0c;请勿关机”(如下图所示)&#xff0c;而且还需求等大约5分钟才干进入系统。这是怎样回事呢&#xff1f;一切都是正常操作的&#xff0c;为什么开时机呈现“正…...

    2022/11/19 21:17:13
  30. 准备配置windows 请勿关闭计算机 蓝屏,Win7开机总是出现提示“配置Windows请勿关机”...

    Win7系统开机启动时总是出现“配置Windows请勿关机”的提示&#xff0c;没过几秒后电脑自动重启&#xff0c;每次开机都这样无法进入系统&#xff0c;此时碰到这种现象的用户就可以使用以下5种方法解决问题。方法一&#xff1a;开机按下F8&#xff0c;在出现的Windows高级启动选…...

    2022/11/19 21:17:12
  31. 准备windows请勿关闭计算机要多久,windows10系统提示正在准备windows请勿关闭计算机怎么办...

    有不少windows10系统用户反映说碰到这样一个情况&#xff0c;就是电脑提示正在准备windows请勿关闭计算机&#xff0c;碰到这样的问题该怎么解决呢&#xff0c;现在小编就给大家分享一下windows10系统提示正在准备windows请勿关闭计算机的具体第一种方法&#xff1a;1、2、依次…...

    2022/11/19 21:17:11
  32. 配置 已完成 请勿关闭计算机,win7系统关机提示“配置Windows Update已完成30%请勿关闭计算机”的解决方法...

    今天和大家分享一下win7系统重装了Win7旗舰版系统后&#xff0c;每次关机的时候桌面上都会显示一个“配置Windows Update的界面&#xff0c;提示请勿关闭计算机”&#xff0c;每次停留好几分钟才能正常关机&#xff0c;导致什么情况引起的呢&#xff1f;出现配置Windows Update…...

    2022/11/19 21:17:10
  33. 电脑桌面一直是清理请关闭计算机,windows7一直卡在清理 请勿关闭计算机-win7清理请勿关机,win7配置更新35%不动...

    只能是等着&#xff0c;别无他法。说是卡着如果你看硬盘灯应该在读写。如果从 Win 10 无法正常回滚&#xff0c;只能是考虑备份数据后重装系统了。解决来方案一&#xff1a;管理员运行cmd&#xff1a;net stop WuAuServcd %windir%ren SoftwareDistribution SDoldnet start WuA…...

    2022/11/19 21:17:09
  34. 计算机配置更新不起,电脑提示“配置Windows Update请勿关闭计算机”怎么办?

    原标题&#xff1a;电脑提示“配置Windows Update请勿关闭计算机”怎么办&#xff1f;win7系统中在开机与关闭的时候总是显示“配置windows update请勿关闭计算机”相信有不少朋友都曾遇到过一次两次还能忍但经常遇到就叫人感到心烦了遇到这种问题怎么办呢&#xff1f;一般的方…...

    2022/11/19 21:17:08
  35. 计算机正在配置无法关机,关机提示 windows7 正在配置windows 请勿关闭计算机 ,然后等了一晚上也没有关掉。现在电脑无法正常关机...

    关机提示 windows7 正在配置windows 请勿关闭计算机 &#xff0c;然后等了一晚上也没有关掉。现在电脑无法正常关机以下文字资料是由(历史新知网www.lishixinzhi.com)小编为大家搜集整理后发布的内容&#xff0c;让我们赶快一起来看一下吧&#xff01;关机提示 windows7 正在配…...

    2022/11/19 21:17:05
  36. 钉钉提示请勿通过开发者调试模式_钉钉请勿通过开发者调试模式是真的吗好不好用...

    钉钉请勿通过开发者调试模式是真的吗好不好用 更新时间:2020-04-20 22:24:19 浏览次数:729次 区域: 南阳 > 卧龙 列举网提醒您:为保障您的权益,请不要提前支付任何费用! 虚拟位置外设器!!轨迹模拟&虚拟位置外设神器 专业用于:钉钉,外勤365,红圈通,企业微信和…...

    2022/11/19 21:17:05
  37. 配置失败还原请勿关闭计算机怎么办,win7系统出现“配置windows update失败 还原更改 请勿关闭计算机”,长时间没反应,无法进入系统的解决方案...

    前几天班里有位学生电脑(windows 7系统)出问题了&#xff0c;具体表现是开机时一直停留在“配置windows update失败 还原更改 请勿关闭计算机”这个界面&#xff0c;长时间没反应&#xff0c;无法进入系统。这个问题原来帮其他同学也解决过&#xff0c;网上搜了不少资料&#x…...

    2022/11/19 21:17:04
  38. 一个电脑无法关闭计算机你应该怎么办,电脑显示“清理请勿关闭计算机”怎么办?...

    本文为你提供了3个有效解决电脑显示“清理请勿关闭计算机”问题的方法&#xff0c;并在最后教给你1种保护系统安全的好方法&#xff0c;一起来看看&#xff01;电脑出现“清理请勿关闭计算机”在Windows 7(SP1)和Windows Server 2008 R2 SP1中&#xff0c;添加了1个新功能在“磁…...

    2022/11/19 21:17:03
  39. 请勿关闭计算机还原更改要多久,电脑显示:配置windows更新失败,正在还原更改,请勿关闭计算机怎么办...

    许多用户在长期不使用电脑的时候&#xff0c;开启电脑发现电脑显示&#xff1a;配置windows更新失败&#xff0c;正在还原更改&#xff0c;请勿关闭计算机。。.这要怎么办呢&#xff1f;下面小编就带着大家一起看看吧&#xff01;如果能够正常进入系统&#xff0c;建议您暂时移…...

    2022/11/19 21:17:02
  40. 还原更改请勿关闭计算机 要多久,配置windows update失败 还原更改 请勿关闭计算机,电脑开机后一直显示以...

    配置windows update失败 还原更改 请勿关闭计算机&#xff0c;电脑开机后一直显示以以下文字资料是由(历史新知网www.lishixinzhi.com)小编为大家搜集整理后发布的内容&#xff0c;让我们赶快一起来看一下吧&#xff01;配置windows update失败 还原更改 请勿关闭计算机&#x…...

    2022/11/19 21:17:01
  41. 电脑配置中请勿关闭计算机怎么办,准备配置windows请勿关闭计算机一直显示怎么办【图解】...

    不知道大家有没有遇到过这样的一个问题&#xff0c;就是我们的win7系统在关机的时候&#xff0c;总是喜欢显示“准备配置windows&#xff0c;请勿关机”这样的一个页面&#xff0c;没有什么大碍&#xff0c;但是如果一直等着的话就要两个小时甚至更久都关不了机&#xff0c;非常…...

    2022/11/19 21:17:00
  42. 正在准备配置请勿关闭计算机,正在准备配置windows请勿关闭计算机时间长了解决教程...

    当电脑出现正在准备配置windows请勿关闭计算机时&#xff0c;一般是您正对windows进行升级&#xff0c;但是这个要是长时间没有反应&#xff0c;我们不能再傻等下去了。可能是电脑出了别的问题了&#xff0c;来看看教程的说法。正在准备配置windows请勿关闭计算机时间长了方法一…...

    2022/11/19 21:16:59
  43. 配置失败还原请勿关闭计算机,配置Windows Update失败,还原更改请勿关闭计算机...

    我们使用电脑的过程中有时会遇到这种情况&#xff0c;当我们打开电脑之后&#xff0c;发现一直停留在一个界面&#xff1a;“配置Windows Update失败&#xff0c;还原更改请勿关闭计算机”&#xff0c;等了许久还是无法进入系统。如果我们遇到此类问题应该如何解决呢&#xff0…...

    2022/11/19 21:16:58
  44. 如何在iPhone上关闭“请勿打扰”

    Apple’s “Do Not Disturb While Driving” is a potentially lifesaving iPhone feature, but it doesn’t always turn on automatically at the appropriate time. For example, you might be a passenger in a moving car, but your iPhone may think you’re the one dri…...

    2022/11/19 21:16:57