【Apollo学习笔记】——规划模块TASK之RULE_BASED_STOP_DECIDER

文章目录

  • 前言
  • RULE_BASED_STOP_DECIDER相关配置
  • RULE_BASED_STOP_DECIDER总体流程
    • StopOnSidePass
      • CheckClearDone
      • CheckSidePassStop
      • IsPerceptionBlocked
      • IsClearToChangeLane
      • CheckSidePassStop
      • BuildStopDecision
      • ELSE:涉及到的一些其他函数
        • NormalizeAngle
        • SelfRotate
    • CheckLaneChangeUrgency
    • AddPathEndStop
  • 参考

前言

在Apollo星火计划学习笔记——Apollo路径规划算法原理与实践与【Apollo学习笔记】——Planning模块讲到……Stage::Process的PlanOnReferenceLine函数会依次调用task_list中的TASK,本文将会继续以LaneFollow为例依次介绍其中的TASK部分究竟做了哪些工作。由于个人能力所限,文章可能有纰漏的地方,还请批评斧正。

modules/planning/conf/scenario/lane_follow_config.pb.txt配置文件中,我们可以看到LaneFollow所需要执行的所有task。

stage_config: {stage_type: LANE_FOLLOW_DEFAULT_STAGEenabled: truetask_type: LANE_CHANGE_DECIDERtask_type: PATH_REUSE_DECIDERtask_type: PATH_LANE_BORROW_DECIDERtask_type: PATH_BOUNDS_DECIDERtask_type: PIECEWISE_JERK_PATH_OPTIMIZERtask_type: PATH_ASSESSMENT_DECIDERtask_type: PATH_DECIDERtask_type: RULE_BASED_STOP_DECIDERtask_type: SPEED_BOUNDS_PRIORI_DECIDERtask_type: SPEED_HEURISTIC_OPTIMIZERtask_type: SPEED_DECIDERtask_type: SPEED_BOUNDS_FINAL_DECIDERtask_type: PIECEWISE_JERK_SPEED_OPTIMIZER# task_type: PIECEWISE_JERK_NONLINEAR_SPEED_OPTIMIZERtask_type: RSS_DECIDER

本文将继续介绍LaneFollow的第8个TASK——RULE_BASED_STOP_DECIDER

基于规则的停止决策是规划模块的任务,属于task中的decider类别。基于规则的停止决策根据一些规则来设置停止标志。

RULE_BASED_STOP_DECIDER相关配置

modules/planning/conf/planning_config.pb.txt

default_task_config: {task_type: RULE_BASED_STOP_DECIDERrule_based_stop_decider_config {max_adc_stop_speed: 0.5max_valid_stop_distance: 1.0search_beam_length: 20.0search_beam_radius_intensity: 0.08search_range: 3.14is_block_angle_threshold: 0.5}
}

modules/planning/proto/task_config.proto

// RuleBasedStopDeciderConfigmessage RuleBasedStopDeciderConfig {optional double max_adc_stop_speed = 1 [default = 0.3];optional double max_valid_stop_distance = 2 [default = 0.5];optional double search_beam_length = 3 [default = 5.0];optional double search_beam_radius_intensity = 4 [default = 0.08];optional double search_range = 5 [default = 3.14];optional double is_block_angle_threshold = 6 [default = 1.57];optional double approach_distance_for_lane_change = 10 [default = 80.0];optional double urgent_distance_for_lane_change = 11 [default = 50.0];
}

RULE_BASED_STOP_DECIDER总体流程

在这里插入图片描述

  • 输入
    apollo::common::Status RuleBasedStopDecider::Process(Frame *const frame, ReferenceLineInfo *const reference_line_info)
    输入是frame和reference_line_info。

  • 输出
    输出保存到reference_line_info中。

代码流程及框架
Process中的代码流程如下图所示。

在这里插入图片描述

apollo::common::Status RuleBasedStopDecider::Process(Frame *const frame, ReferenceLineInfo *const reference_line_info) {// 1. Rule_based stop for side pass onto reverse laneStopOnSidePass(frame, reference_line_info);// 2. Rule_based stop for urgent lane changeif (FLAGS_enable_lane_change_urgency_checking) {CheckLaneChangeUrgency(frame);}// 3. Rule_based stop at path end positionAddPathEndStop(frame, reference_line_info);return Status::OK();
}

主要核心的函数就是StopOnSidePassCheckLaneChangeUrgency以及AddPathEndStop,接着分别对三者进行剖析。

StopOnSidePass

在这里插入图片描述
在这里插入图片描述

void RuleBasedStopDecider::StopOnSidePass(Frame *const frame, ReferenceLineInfo *const reference_line_info) {static bool check_clear;// 默认falsestatic common::PathPoint change_lane_stop_path_point;// 获取path dataconst PathData &path_data = reference_line_info->path_data();double stop_s_on_pathdata = 0.0;// 找到"self"类型的路径,returnif (path_data.path_label().find("self") != std::string::npos) {check_clear = false;change_lane_stop_path_point.Clear();return;}// CheckClearDone:Check if needed to check clear again for side pass// 如果check_clear为true,且CheckClearDone成功。设置check_clear为falseif (check_clear &&CheckClearDone(*reference_line_info, change_lane_stop_path_point)) {check_clear = false;}// CheckSidePassStop:Check if necessary to set stop fence used for nonscenario side pass// 如果check_clear为false,CheckSidePassStop为trueif (!check_clear &&CheckSidePassStop(path_data, *reference_line_info, &stop_s_on_pathdata)) {// 如果障碍物没有阻塞且可以换道,直接returnif (!LaneChangeDecider::IsPerceptionBlocked(*reference_line_info,rule_based_stop_decider_config_.search_beam_length(),rule_based_stop_decider_config_.search_beam_radius_intensity(),rule_based_stop_decider_config_.search_range(),rule_based_stop_decider_config_.is_block_angle_threshold()) &&LaneChangeDecider::IsClearToChangeLane(reference_line_info)) {return;}// 检查adc是否停在了stop fence前,否返回trueif (!CheckADCStop(path_data, *reference_line_info, stop_s_on_pathdata)) {// 设置stop fence,成功就执行 check_clear = true;if (!BuildSidePassStopFence(path_data, stop_s_on_pathdata,&change_lane_stop_path_point, frame,reference_line_info)) {AERROR << "Set side pass stop fail";}} else {if (LaneChangeDecider::IsClearToChangeLane(reference_line_info)) {check_clear = true;}}}
}

CheckClearDone

// Check if needed to check clear again for side pass
bool RuleBasedStopDecider::CheckClearDone(const ReferenceLineInfo &reference_line_info,const common::PathPoint &stop_point) {// 获取ADC的SL坐标const double adc_front_edge_s = reference_line_info.AdcSlBoundary().end_s();const double adc_back_edge_s = reference_line_info.AdcSlBoundary().start_s();const double adc_start_l = reference_line_info.AdcSlBoundary().start_l();const double adc_end_l = reference_line_info.AdcSlBoundary().end_l();double lane_left_width = 0.0;double lane_right_width = 0.0;reference_line_info.reference_line().GetLaneWidth((adc_front_edge_s + adc_back_edge_s) / 2.0, &lane_left_width,&lane_right_width);SLPoint stop_sl_point;// 获取停止点的SL坐标reference_line_info.reference_line().XYToSL(stop_point, &stop_sl_point);// use distance to last stop point to determine if needed to check clear// againif (adc_back_edge_s > stop_sl_point.s()) {if (adc_start_l > -lane_right_width || adc_end_l < lane_left_width) {return true;}}return false;
}

CheckSidePassStop

// @brief Check if necessary to set stop fence used for nonscenario side pass
bool RuleBasedStopDecider::CheckSidePassStop(const PathData &path_data, const ReferenceLineInfo &reference_line_info,double *stop_s_on_pathdata) {const std::vector<std::tuple<double, PathData::PathPointType, double>>&path_point_decision_guide = path_data.path_point_decision_guide();// 初始化类型PathData::PathPointType last_path_point_type =PathData::PathPointType::UNKNOWN;// 遍历 path_point_decision_guidefor (const auto &point_guide : path_point_decision_guide) {// 若上一点在车道内,这一点在逆行车道上if (last_path_point_type == PathData::PathPointType::IN_LANE &&std::get<1>(point_guide) ==PathData::PathPointType::OUT_ON_REVERSE_LANE) {*stop_s_on_pathdata = std::get<0>(point_guide);// Approximate the stop fence s based on the vehicle positionconst auto &vehicle_config =common::VehicleConfigHelper::Instance()->GetConfig();const double ego_front_to_center =vehicle_config.vehicle_param().front_edge_to_center();common::PathPoint stop_pathpoint;// 获取stop pointif (!path_data.GetPathPointWithRefS(*stop_s_on_pathdata,&stop_pathpoint)) {AERROR << "Can't get stop point on path data";return false;}const double ego_theta = stop_pathpoint.theta();Vec2d shift_vec{ego_front_to_center * std::cos(ego_theta),ego_front_to_center * std::sin(ego_theta)};// stop_fence的位置const Vec2d stop_fence_pose =shift_vec + Vec2d(stop_pathpoint.x(), stop_pathpoint.y());double stop_l_on_pathdata = 0.0;const auto &nearby_path = reference_line_info.reference_line().map_path();nearby_path.GetNearestPoint(stop_fence_pose, stop_s_on_pathdata,&stop_l_on_pathdata);return true;}last_path_point_type = std::get<1>(point_guide);}return false;
}

IsPerceptionBlocked

参数解释:

search_beam_length 扫描长度
search_beam_radius_intensity 扫描间隔
search_range 依据ADC中心的扫描范围
is_block_angle_threshold 筛选障碍物所占角度大小的阈值

bool LaneChangeDecider::IsPerceptionBlocked(const ReferenceLineInfo& reference_line_info,const double search_beam_length, const double search_beam_radius_intensity,const double search_range, const double is_block_angle_threshold) {// search_beam_length: 20.0 //is the length of scanning beam// search_beam_radius_intensity: 0.08 //is the resolution of scanning// search_range: 3.14 	//is the scanning range centering at ADV heading// is_block_angle_threshold: 0.5 //is the threshold to tell how big a block angle range is perception blocking// 获取车辆状态、位置、航向角const auto& vehicle_state = reference_line_info.vehicle_state();const common::math::Vec2d adv_pos(vehicle_state.x(), vehicle_state.y());const double adv_heading = vehicle_state.heading();// 遍历障碍物for (auto* obstacle :reference_line_info.path_decision().obstacles().Items()) {// NormalizeAngle将给定的角度值规范化到一个特定的范围内(-π到π之间)double left_most_angle =common::math::NormalizeAngle(adv_heading + 0.5 * search_range);double right_most_angle =common::math::NormalizeAngle(adv_heading - 0.5 * search_range);bool right_most_found = false;// 跳过虚拟障碍物if (obstacle->IsVirtual()) {ADEBUG << "skip one virtual obstacle";continue;}// 获取障碍物多边形const auto& obstacle_polygon = obstacle->PerceptionPolygon();// 按角度进行搜索for (double search_angle = 0.0; search_angle < search_range;search_angle += search_beam_radius_intensity) {common::math::Vec2d search_beam_end(search_beam_length, 0.0);const double beam_heading = common::math::NormalizeAngle(adv_heading - 0.5 * search_range + search_angle);// search_beam_end绕adv_pos旋转beam_heading角度search_beam_end.SelfRotate(beam_heading);search_beam_end += adv_pos;// 构造线段common::math::LineSegment2d search_beam(adv_pos, search_beam_end);// 判断最右边界是否找到,并更新右边界角度if (!right_most_found && obstacle_polygon.HasOverlap(search_beam)) {right_most_found = true;right_most_angle = beam_heading;}// 如果最右边界已找到,且障碍物的感知多边形与搜索光束无重叠,则更新左边界角度并跳出循环。if (right_most_found && !obstacle_polygon.HasOverlap(search_beam)) {left_most_angle = beam_heading;break;}}// 如果最右边界未找到,则继续处理下一个障碍物。(说明该障碍物不在搜索范围内)if (!right_most_found) {// obstacle is not in search rangecontinue;}// 判断阈值,过滤掉小的障碍物if (std::fabs(common::math::NormalizeAngle(left_most_angle - right_most_angle)) > is_block_angle_threshold) {return true;}}return false;
}

IsClearToChangeLane

这个在【Apollo学习笔记】——规划模块TASK之LANE_CHANGE_DECIDER已经有过介绍。

CheckSidePassStop

// @brief Check if necessary to set stop fence used for nonscenario side pass
bool RuleBasedStopDecider::CheckSidePassStop(const PathData &path_data, const ReferenceLineInfo &reference_line_info,double *stop_s_on_pathdata) {const std::vector<std::tuple<double, PathData::PathPointType, double>>&path_point_decision_guide = path_data.path_point_decision_guide();// 初始化类型PathData::PathPointType last_path_point_type =PathData::PathPointType::UNKNOWN;// 遍历 path_point_decision_guidefor (const auto &point_guide : path_point_decision_guide) {// 若上一点在车道内,这一点在逆行车道上if (last_path_point_type == PathData::PathPointType::IN_LANE &&std::get<1>(point_guide) ==PathData::PathPointType::OUT_ON_REVERSE_LANE) {*stop_s_on_pathdata = std::get<0>(point_guide);// Approximate the stop fence s based on the vehicle positionconst auto &vehicle_config =common::VehicleConfigHelper::Instance()->GetConfig();const double ego_front_to_center =vehicle_config.vehicle_param().front_edge_to_center();common::PathPoint stop_pathpoint;// 获取stop pointif (!path_data.GetPathPointWithRefS(*stop_s_on_pathdata,&stop_pathpoint)) {AERROR << "Can't get stop point on path data";return false;}const double ego_theta = stop_pathpoint.theta();Vec2d shift_vec{ego_front_to_center * std::cos(ego_theta),ego_front_to_center * std::sin(ego_theta)};// stop_fence的位置const Vec2d stop_fence_pose =shift_vec + Vec2d(stop_pathpoint.x(), stop_pathpoint.y());double stop_l_on_pathdata = 0.0;const auto &nearby_path = reference_line_info.reference_line().map_path();nearby_path.GetNearestPoint(stop_fence_pose, stop_s_on_pathdata,&stop_l_on_pathdata);return true;}last_path_point_type = std::get<1>(point_guide);}return false;
}

BuildStopDecision

/** @brief: build virtual obstacle of stop wall, and add STOP decision*/
int BuildStopDecision(const std::string& stop_wall_id, const double stop_line_s,const double stop_distance,const StopReasonCode& stop_reason_code,const std::vector<std::string>& wait_for_obstacles,const std::string& decision_tag, Frame* const frame,ReferenceLineInfo* const reference_line_info) {CHECK_NOTNULL(frame);CHECK_NOTNULL(reference_line_info);// 检查停止线是否在参考线上const auto& reference_line = reference_line_info->reference_line();if (!WithinBound(0.0, reference_line.Length(), stop_line_s)) {AERROR << "stop_line_s[" << stop_line_s << "] is not on reference line";return 0;}// create virtual stop wallconst auto* obstacle =frame->CreateStopObstacle(reference_line_info, stop_wall_id, stop_line_s);if (!obstacle) {AERROR << "Failed to create obstacle [" << stop_wall_id << "]";return -1;}const Obstacle* stop_wall = reference_line_info->AddObstacle(obstacle);if (!stop_wall) {AERROR << "Failed to add obstacle[" << stop_wall_id << "]";return -1;}// build stop decisionconst double stop_s = stop_line_s - stop_distance;const auto& stop_point = reference_line.GetReferencePoint(stop_s);const double stop_heading =reference_line.GetReferencePoint(stop_s).heading();ObjectDecisionType stop;auto* stop_decision = stop.mutable_stop();stop_decision->set_reason_code(stop_reason_code);stop_decision->set_distance_s(-stop_distance);stop_decision->set_stop_heading(stop_heading);stop_decision->mutable_stop_point()->set_x(stop_point.x());stop_decision->mutable_stop_point()->set_y(stop_point.y());stop_decision->mutable_stop_point()->set_z(0.0);for (size_t i = 0; i < wait_for_obstacles.size(); ++i) {stop_decision->add_wait_for_obstacle(wait_for_obstacles[i]);}auto* path_decision = reference_line_info->path_decision();path_decision->AddLongitudinalDecision(decision_tag, stop_wall->Id(), stop);return 0;
}

ELSE:涉及到的一些其他函数

NormalizeAngle

NormalizeAngle将给定的角度值规范化到一个特定的范围内(-π到π之间)

double NormalizeAngle(const double angle) {double a = std::fmod(angle + M_PI, 2.0 * M_PI);if (a < 0.0) {a += (2.0 * M_PI);}return a - M_PI;
}

SelfRotate

将向量绕原点旋转 a n g l e angle angle角。

void Vec2d::SelfRotate(const double angle) {double tmp_x = x_;x_ = x_ * cos(angle) - y_ * sin(angle);y_ = tmp_x * sin(angle) + y_ * cos(angle);
}

CheckLaneChangeUrgency

检查紧急换道,当FLAGS_enable_lane_change_urgency_checking为true时,启用函数。
在这里插入图片描述在这里插入图片描述

void RuleBasedStopDecider::CheckLaneChangeUrgency(Frame *const frame) {// 直接进入循环,检查每个reference_line_infofor (auto &reference_line_info : *frame->mutable_reference_line_info()) {// Check if the target lane is blocked or not// 1. 检查目标道路是否阻塞,如果在change lane path上,就跳过if (reference_line_info.IsChangeLanePath()) {is_clear_to_change_lane_ =LaneChangeDecider::IsClearToChangeLane(&reference_line_info);is_change_lane_planning_succeed_ =reference_line_info.Cost() < kStraightForwardLineCost;continue;}// If it's not in lane-change scenario || (target lane is not blocked &&// change lane planning succeed), skip// 2.如果不是换道的场景,或者(目标lane没有阻塞)并且换道规划成功,跳过if (frame->reference_line_info().size() <= 1 ||(is_clear_to_change_lane_ && is_change_lane_planning_succeed_)) {continue;}// When the target lane is blocked in change-lane case, check the urgency// Get the end point of current routingconst auto &route_end_waypoint =reference_line_info.Lanes().RouteEndWaypoint();// If can't get lane from the route's end waypoint, then skip// 3.在route的末端无法获得lane,跳过if (!route_end_waypoint.lane) {continue;}auto point = route_end_waypoint.lane->GetSmoothPoint(route_end_waypoint.s);auto *reference_line = reference_line_info.mutable_reference_line();common::SLPoint sl_point;// Project the end point to sl_point on current reference lane// 将当前参考线的点映射到frenet坐标系下if (reference_line->XYToSL(point, &sl_point) &&reference_line->IsOnLane(sl_point)) {// Check the distance from ADC to the end point of current routingdouble distance_to_passage_end =sl_point.s() - reference_line_info.AdcSlBoundary().end_s();// If ADC is still far from the end of routing, no need to stop, skip// 4. 如果adc距离routing终点较远,不需要停止,跳过if (distance_to_passage_end >rule_based_stop_decider_config_.approach_distance_for_lane_change()) {continue;}// In urgent case, set a temporary stop fence and wait to change lane// TODO(Jiaxuan Xu): replace the stop fence to more intelligent actions// 5.如果遇到紧急情况,设置临时的stop fence,等待换道const std::string stop_wall_id = "lane_change_stop";std::vector<std::string> wait_for_obstacles;util::BuildStopDecision(stop_wall_id, sl_point.s(),rule_based_stop_decider_config_.urgent_distance_for_lane_change(),StopReasonCode::STOP_REASON_LANE_CHANGE_URGENCY, wait_for_obstacles,"RuleBasedStopDecider", frame, &reference_line_info);}}
}

AddPathEndStop

在这里插入图片描述

void RuleBasedStopDecider::AddPathEndStop(Frame *const frame, ReferenceLineInfo *const reference_line_info) {// 路径不为空且起点到终点的距离不小于20mif (!reference_line_info->path_data().path_label().empty() &&reference_line_info->path_data().frenet_frame_path().back().s() -reference_line_info->path_data().frenet_frame_path().front().s() <FLAGS_short_path_length_threshold) { // FLAGS_short_path_length_threshold: Threshold for too short path length(20m)// 创建虚拟墙的IDconst std::string stop_wall_id =PATH_END_VO_ID_PREFIX + reference_line_info->path_data().path_label();std::vector<std::string> wait_for_obstacles;// 创建stop fenceutil::BuildStopDecision(stop_wall_id,reference_line_info->path_data().frenet_frame_path().back().s() - 5.0,0.0, StopReasonCode::STOP_REASON_REFERENCE_END, wait_for_obstacles,"RuleBasedStopDecider", frame, reference_line_info);}
}

参考

[1] 基于规则的停止决策

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.mzph.cn/news/65666.shtml

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

相关文章

macOS上制作arm64的jdk17镜像

公司之前一直用的openjdk17的镜像&#xff0c;docker官网可以直接下载&#xff0c;但是最近对接的一个项目&#xff0c;对方用的是jdk17&#xff0c;在对接的时候有加解密异常的问题&#xff0c;为了排查是不是jdk版本的问题&#xff0c;需要制作jdk17的镜像。docker官网上的第…

iOS开发Swift-4-IBAction,group,音乐播放器-木琴App

1.使用素材创建木琴App的UI。 2.连接IBAction。 其余按钮直接拖拽到play里边。 当鼠标置于1处时2处显示如图&#xff0c;表示成功。当用户按下任一按钮都会触发play中的内容。 3.将7个按钮的View中的Tag值分别调为1、2、3、4、5、6、7. 4.将音频文件拖入项目文件中。 Create gr…

Leetcode19 删除链表指定节点

思路&#xff1a;用列表保存链表&#xff0c;然后分情况讨论。 class Solution:def removeNthFromEnd(self, head, n: int):node_list[head]while head.next:headhead.nextnode_list.append(head)remove_loclen(node_list)-n#要移除的位置if len(node_list)1:return Noneif re…

Python小知识 - 一个简单的Python爬虫实例

一个简单的Python爬虫实例 这是一个简单的Python爬虫实例&#xff0c;我们将使用urllib库来下载一个网页并解析它。 首先&#xff0c;我们需要安装urllib库&#xff1a; pip install urllib接下来&#xff0c;我们来看看如何使用urllib库来下载一个网页&#xff1a; import url…

运行命令出现错误 /bin/bash^M: bad interpreter: No such file or directory

在系统上运行一个 Linux 的命令的时候出现下面的错误信息&#xff1a; -bash: ./build.sh: /bin/bash^M: bad interpreter: No such file or directory 这个是在 Windows 作为 WSL 的时候出的错误。 原因和解决 出现问题的原因在于脚本在 Windows 中使用的回车换行和 Linux …

从零开始搭建AI网站(6):如何使用响应式编程

响应式编程&#xff08;Reactive Programming&#xff09;是一种编程范式&#xff0c;旨在处理异步数据流和事件流。它通过使用观察者模式和函数式编程的概念&#xff0c;将数据流和事件流抽象为可观察的序列&#xff0c;然后通过操作这些序列来实现各种功能。 在响应式编程中…

Navicat连接数据库报2003错误解决办法

是防火墙还没有开启 查看防火墙管理的端口 设置3306防火墙开启&#xff0c;重载防火墙 连接成功

睿趣科技:抖音开小店大概多久可以做起来

随着移动互联网的快速发展&#xff0c;社交媒体平台成为了人们分享生活、交流信息的主要渠道之一。在众多社交平台中&#xff0c;抖音以其独特的短视频形式和强大的用户粘性受到了广泛关注。近年来&#xff0c;越来越多的人通过在抖音上开设小店来实现创业梦想&#xff0c;这种…

XSS漏洞及分析

目录 1.什么是xss漏洞 1&#xff09;存储型XSS漏洞 2&#xff09;反射型XSS漏洞 3&#xff09;DOM型XSS漏洞 2.什么是domcobble破环 3.案例一 1&#xff09;例题链接 2&#xff09;代码展示 3&#xff09;例题分析 4.案例二 1&#xff09;例题链接 2&#xff09;代…

【ArcGIS Pro二次开发】(65):进出平衡SHP转TXT、TXT转SHP

最近一个小伙伴提了这么一个需求&#xff0c;需要把TXT和SHP进行互转。 这种TXT文件其实遇到了好几个版本&#xff0c;都有一点小差异。之前已经做过一个TXT转SHP的工具&#xff0c;但好像不适用。于是针对这个版本&#xff0c;做了互转的2个工具。 【SHP转TXT】 一、要实现的…

用于设计和分析具有恒定近心点半径的低推力螺旋轨迹研究(Matlab代码实现)

&#x1f4a5;&#x1f4a5;&#x1f49e;&#x1f49e;欢迎来到本博客❤️❤️&#x1f4a5;&#x1f4a5; &#x1f3c6;博主优势&#xff1a;&#x1f31e;&#x1f31e;&#x1f31e;博客内容尽量做到思维缜密&#xff0c;逻辑清晰&#xff0c;为了方便读者。 ⛳️座右铭&a…

【LeetCode】剑指 Offer <二刷>(3)

目录 题目&#xff1a;剑指 Offer 06. 从尾到头打印链表 - 力扣&#xff08;LeetCode&#xff09; 题目的接口&#xff1a; 解题思路&#xff1a; 代码&#xff1a; 过啦&#xff01;&#xff01;&#xff01; 题目&#xff1a;剑指 Offer 07. 重建二叉树 - 力扣&#xf…

A 股个股资金流 API 数据接口

A 股个股资金流 API 数据接口 全量股票资金流数据&#xff0c;全量A股数据&#xff0c;最长30日历史数据 1. 产品功能 支持所有A股资金流数据查询&#xff1b;每日定时更新数据&#xff1b;支持多达 30 日历史数据查询&#xff1b;超高的查询效率&#xff0c;数据秒级返回&am…

探索树堆Treap和红黑树的优势和劣势

探索树堆Treap和红黑树的优势和劣势 一、背景知识二、树堆&#xff08;Treap&#xff09;的介绍三、红黑树&#xff08;RB-Tree&#xff09;的介绍四、树堆&#xff08;Treap&#xff09;与红黑树&#xff08;RB-Tree&#xff09;的比较总结 博主简介 &#x1f4a1;一个热爱分享…

【Mysql问题集锦】:Can‘t create table ‘#sql-58d7_431d‘ (errno: 28)

问题描述&#xff1a; 问题原因&#xff1a; OSError: [Errno 28] No space left on device&#xff0c;即&#xff1a;磁盘空间不足&#xff0c;无法创建文件。因此&#xff0c;导致Mysql无法执行SQL语句。 问题解法&#xff1a; Step 1&#xff0c;查看有哪些目录占用了大量…

已解决“SyntaxError: invalid character in identifier“报错问题

本文摘要&#xff1a;本文已解决 Python FileNotFoundError 的相关报错问题&#xff0c;并总结提出了几种可用解决方案。同时结合人工智能GPT排除可能得隐患及错误。 &#x1f60e; 作者介绍&#xff1a;我是程序员洲洲&#xff0c;一个热爱写作的非著名程序员。CSDN全栈优质领…

vmware虚拟机(ubuntu)远程开发golang、python环境安装

目录 1. 下载vmware2. 下载ubuntu镜像3. 安装4. 做一些设置4.1 分辨率设置4.2 语言下载4.3 输入法设置4.4 时区设置 5. 直接切换管理员权限6. 网络6.1 看ip6.2 ssh 7. 本地编译器连接远程服务器7.1 创建远程部署的配置7.2 文件同步7.3 远程启动项目 8. ubuntu安装golang环境8.1…

SQL查询本年每月的数据

--一、以一行数据的形式&#xff0c;显示本年的12月的数据&#xff0c;本示例以2017年为例&#xff0c;根据统计日期字段判断&#xff0c;计算总和&#xff0c;查询语句如下&#xff1a;selectsum(case when datepart(month,统计日期)1 then 支付金额 else 0 end) as 1月, sum…

初探---Qt

目录 一、介绍Qt 二、软件安装 三、QT工具介绍 四、Assistant帮助文档的使用 五、设计师界面的介绍 ​编辑 六、QT工程项目各文件初始程序的介绍 1> 配置文件&#xff1a;.pro文件 2> 头文件 3> 源文件 4> 主程序 5> 各文件之间调用方式 七、第一个…

【LeetCode】双指针妙解有效三角形的个数

Problem: 611. 有效三角形的个数 文章目录 题目分析讲解算法原理复杂度Code 题目分析 首先我们来分析一下本题的思路 看到题目中给出的示例 题目的意思很简单&#xff0c;就是将给到的数字去做一个组合&#xff0c;然后看看这三条边是否可以构成三角形。那判断的方法不用我说&a…