路径规划-DWA算法(C++实现)

news2024/11/19 13:22:11

1、简单介绍

DWA算法(dynamic window approach),其原理主要是在速度空间(v,w)中采样多组速度,并模拟出这些速度在一定时间内的运动轨迹,并通过评价函数对这些轨迹进行评价(其中包括距离障碍物距离,距离目标点距离等等进行评价),选取最优轨迹对应的(v,w)驱动机器人运动。

2、原理

2.1、运动学模型

1)非全向运动:只能前进和旋转(相邻时刻码盘采样,近似直线v*detaT)

x = x + V Δ t cos ⁡ ( θ t ) x = x+V\Delta t \cos(\theta_{t}) x=x+VΔtcos(θt).
y = y + V Δ t sin ⁡ ( θ t ) y = y+V\Delta t \sin(\theta_{t}) y=y+VΔtsin(θt).
θ t = θ t + w Δ t \theta_{t} =\theta_{t}+w\Delta t θt=θt+wΔt.
在这里插入图片描述

2) 全向运动:存在y上的速度

需要把y轴的移动距离投影到世界坐标系即可
Δ x = v y Δ t cos ⁡ ( θ t + π / 2 ) = − v y Δ t sin ⁡ ( θ t ) \Delta x = v_{y}\Delta t\cos(\theta_{t}+\pi/2) = -v_{y}\Delta t\sin(\theta_{t}) Δx=vyΔtcos(θt+π/2)=vyΔtsin(θt)
Δ y = v y Δ t sin ⁡ ( θ t + π / 2 ) = v y Δ t cos ⁡ ( θ t ) \Delta y = v_{y}\Delta t\sin(\theta_{t}+\pi/2) = v_{y}\Delta t\cos(\theta_{t}) Δy=vyΔtsin(θt+π/2)=vyΔtcos(θt)
把y的投影加上上方的的公式
x = x + V Δ t cos ⁡ ( θ t ) − v y Δ t sin ⁡ ( θ t ) x = x+V\Delta t \cos(\theta_{t})-v_{y}\Delta t\sin(\theta_{t}) x=x+VΔtcos(θt)vyΔtsin(θt).
y = y + V Δ t sin ⁡ ( θ t ) + v y Δ t cos ⁡ ( θ t ) y = y+V\Delta t \sin(\theta_{t})+v_{y}\Delta t\cos(\theta_{t}) y=y+VΔtsin(θt)+vyΔtcos(θt).
θ t = θ t + w Δ t \theta_{t} =\theta_{t}+w\Delta t θt=θt+wΔt.
需要补充说明的是,令 v ( t ) v_{(t)} v(t)=0,上式与1)中公式表达式完全相同,故ROS中采用2)中的公式进行计算,所以DWA算法适用于两轮差速和全向移动机器人。

2.2 、速度空间(v,w)

机器人的轨迹运动模型有了,根据速度就可以推算出轨迹。因此只需采样很多速度,推算轨迹,然后评价这些轨迹好不好就行了

  • 移动机器人受自身最大速度最小速度的限制
  • 移动机器人受加速度的影响

由于加速度有一个范围限制,所以最大加速度或最大减速度一定时间内能达到的速度 ,才会被保留,表达式如下:
在这里插入图片描述

  • 移动机器人受障碍的影响

为了能在碰到障碍物前停下来,在最大减速度的条件下,速度满足以下条件:
在这里插入图片描述
其中dist(v,w)为(v,w)对应的轨迹上里障碍物最近的距离。

在上述三条约束条件的限制下,速度空间(v,w)会有一定的范围,另外会随着电机的线加速度、角加速度进行变换,速度空间会动态变化,我们将其称为动态窗口。在满足约束条件的情况下,进行采样(v,w),可以得到相应的轨迹:
在这里插入图片描述

2.3、评价函数

在速度空间(v,w)中采样,根据运动学模型推测对应的轨迹,接下来引入评价函数,对轨迹进行打分,选取最优的轨迹。

一般来说,评价函数如下:
在这里插入图片描述
其中,heading(v,w)为方位角评价函数:评价机器人在当前的设定的速度下,轨迹末端朝向与目标点之间的角度差距;dist(v,w) 主要的意义为机器人处于预测轨迹末端点位置时与地图上最近障碍物的距离,对于靠近障碍物的采样点进行惩罚,确保机器人的避障能力,降低机器人与障碍物发生碰撞的概率;velocity(v,w)为当前机器人的线速度,为了促进机器人快速到达目标; α , β , γ \alpha , \beta,\gamma α,β,γ为权重。当然,可以对评价函数进行优化,添加更多的评价函数指标。

2.4 、注意事项

  • 如果是出小车一直后退,可以通过设置最小速度来避免
  • 如果出现,小车无法行走,应该检查一些最大加速度在给定的时间间隔内是否大于最小速度,若不大于最小速度则无法得到有效速度。
  • 如果,小车遇到障碍物无法躲避应该把预测时间调大一些试试

2.5 、应用场景

计算复杂度低: 只考虑安全的轨迹,每次采样的时间较短,可以实时避障
应用模型: 适用于两轮差分和全向移动模型、不能用在阿克曼模型。
缺点:
(1)前瞻性不足: 只模拟并评价了下一步,如在机器人前段遇见“C”字形障碍时,不能很好的避障
(2)非全局最优路径: 每次都选择下一步的最佳路径,而非全局最优路径

以上理论参考参考

3、C++实现

代码中的变量设置需要进行修改


#ifndef DWA_H
#define DWA_H

#include <float.h>
#include <math.h>

#include <iostream>
#include <queue>
#include <vector>
using namespace std;
#define PI 3.1415926
struct Car
{
  float max_speed = 0.4;
  float min_speed = 0.05;
  float max_angular_speed = 14 * PI / 180.0;  // 0.26
  float min_angular_speed = -14 * PI / 180.0;
  float max_accel = 0.6;
  float max_angular_speed_rate = 7 * PI / 180;  // 0.122
  float v_resolution = 0.01;                    // 速度采样分辨率
  float yaw_rate_resolution = PI / 180;
  float dt = 0.1;  //运动学模型预测时间
  float predict_time = 6.0;
  float goal_cost_gain = 0.15;
  float speed_cost_gain = 1.0;
  float obstacle_cost_gain = 1.0;
  float dis_cost_gain = 0.2;
  float radius = 0.3;
};
struct State
{
  float x;
  float y;
  float yaw;
  float speed;
  float angular_speed;
  State(){};
  State(float x_, float y_, float yaw_, float speed_, float angular_speed_)
      : x(x_), y(y_), yaw(yaw_), speed(speed_), angular_speed(angular_speed_)
  {
  }
};

class DWA2
{
 public:
  DWA2();
  vector<float> dwaControl(const State &CState);
  void dwaControl(const std::vector<float> &robotState,
                  const std::vector<float> &goal,
                  const std::vector<std::vector<float>> &obstacle,
                  vector<float> &bestSpeed,
                  std::vector<std::vector<float>> &nextpath,
                  const int type = 1);
  void dwaControl(
      const std::vector<float> &robotState, const std::vector<float> &goal,
      std::queue<std::vector<std::vector<std::vector<float>>>> &obstacle,
      vector<float> &bestSpeed, std::vector<std::vector<float>> &nextpath,
      const int type = 1);

 private:
  vector<float> calcDw(const State &CState);
  void calcBestSpeed(const State &CState, const vector<float> &dw,
                     const int type = 1);
  void calcBestSpeed(const State &CState, const vector<float> &dw,
                     const std::vector<std::vector<float>> &obstacle,
                     vector<float> &bestSpeed,
                     std::vector<std::vector<float>> &nextpath,
                     const int type = 1);
  void calcBestSpeed(
      const State &CState, const vector<float> &dw,
      std::queue<std::vector<std::vector<std::vector<float>>>> &obstacle,
      vector<float> &bestSpeed, std::vector<std::vector<float>> &nextpath,
      const int type = 1);
  void predictTrajectory(const State &CState, const float &speed,
                         const float &angular_speed, vector<State> &trajectory,
                         const int type = 1);
  State motionModel(const State &CState, const float &speed,
                    const float &angular_speed, const int type = 1);
  float calcGoalCost(const vector<State> &trajectory);

  float calcObstacleCost(const vector<State> &trajectory);
  float calcObstacleCost(const vector<State> &trajectory,
                         const std::vector<std::vector<float>> &obstacle,
                         bool &flag);
  float calcObstacleCost(
      const vector<State> &trajectory,
      std::queue<std::vector<std::vector<std::vector<float>>>> &obstacle_,
      bool &flag);

  double getAng(double now_x, double now_y, double tar_x, double tar_y,
                double now_ang);
  Car car;
  vector<vector<State>> trajectory;
  State destinationState;
  bool aaa = false;
  int leftTrun = 0;
  int rightTrun = 0;
};

#endif  // DWA_H

//动态窗口法
void DWA2::dwaControl(const std::vector<float> &robotState,
                      const std::vector<float> &goal,
                      const std::vector<std::vector<float>> &obstacle,
                      vector<float> &bestSpeed,
                      std::vector<std::vector<float>> &nextpath, const int type)
{
  State currentState(robotState[0], robotState[1], robotState[2], robotState[3],
                     robotState[4]);
  destinationState.x = goal[0];
  destinationState.y = goal[1];
  vector<float> dw(
      4);  // dw[0]为最小速度,dw[1]为最大速度,dw[2]为最小角速度,dw[3]为最大角速度
  //计算动态窗口
  dw = calcDw(currentState);
  //计算最佳(v, w)
  calcBestSpeed(currentState, dw, obstacle, bestSpeed, nextpath, type);
  return;
}
void DWA2::dwaControl(
    const std::vector<float> &robotState, const std::vector<float> &goal,
    std::queue<std::vector<std::vector<std::vector<float>>>> &obstacle,
    vector<float> &bestSpeed, std::vector<std::vector<float>> &nextpath,
    const int type)
{
  State currentState(robotState[0], robotState[1], robotState[2], robotState[3],
                     robotState[4]);
  destinationState.x = goal[0];
  destinationState.y = goal[1];
  // dw[0]为最小速度,dw[1]为最大速度,dw[2]为最小角速度,dw[3]为最大角速度
  vector<float> dw(4);
  //计算动态窗口
  dw = calcDw(currentState);
  //计算最佳(v, w)
  calcBestSpeed(currentState, dw, obstacle, bestSpeed, nextpath, type);
  return;
}
// 计算动态窗口
vector<float> DWA2::calcDw(const State &CState)
{
  // 机器人速度属性限制的动态窗口
  vector<float> dw_robot_state{car.min_speed, car.max_speed,
                               car.min_angular_speed, car.max_angular_speed};
  // 机器人模型限制的动态窗口
  vector<float> dw_robot_model(4);
  dw_robot_model[0] = CState.speed - car.max_accel * car.dt;
  dw_robot_model[1] = CState.speed + car.max_accel * car.dt;
  dw_robot_model[2] =
      CState.angular_speed - car.max_angular_speed_rate * car.dt;
  dw_robot_model[3] =
      CState.angular_speed + car.max_angular_speed_rate * car.dt;
  vector<float> dw{
      max(max(dw_robot_state[0], dw_robot_model[0]), car.min_speed),
      min(dw_robot_state[1], dw_robot_model[1]),
      max(dw_robot_state[2], dw_robot_model[2]),
      min(dw_robot_state[3], dw_robot_model[3])};
  // std::cout<<"dw : "<<dw[0]<<" "<<dw[1]<<" "<<dw[2]<<" "<<dw[3]<<"
  // "<<CState.angular_speed <<std::endl;
  return dw;
}

void DWA2::calcBestSpeed(const State &CState, const vector<float> &dw,
                         const std::vector<std::vector<float>> &obstacle,
                         vector<float> &bestSpeed,
                         std::vector<std::vector<float>> &nextpath,
                         const int type)
{
  vector<float> best_speed{0, 0};
  vector<State> trajectoryTmp;
  vector<State> trajectory;
  float min_cost = 10000;
  float final_cost;
  float goal_cost;
  float speed_cost = 0;
  float obstacle_cost = 0;
  float distance_cost = 0;
  std::vector<std::vector<float>> temobs = obstacle;
  for (float i = dw[0]; i < dw[1]; i += car.v_resolution)
  {
    for (float j = dw[2]; j < dw[3]; j += car.yaw_rate_resolution)
    {
      //预测轨迹
      trajectoryTmp.clear();
      predictTrajectory(CState, i, j, trajectoryTmp, type);
      //计算代价
      goal_cost = car.goal_cost_gain * calcGoalCost(trajectoryTmp);
      speed_cost =
          car.speed_cost_gain * (car.max_speed - trajectoryTmp.back().speed);
      bool flag = true;
      obstacle_cost = car.obstacle_cost_gain *
                      calcObstacleCost(trajectoryTmp, obstacle, flag);
      distance_cost = car.dis_cost_gain *
                      sqrt(pow(destinationState.x - trajectoryTmp.back().x, 2) +
                           pow(destinationState.y - trajectoryTmp.back().y, 2));
      final_cost = goal_cost + speed_cost + obstacle_cost + distance_cost;

      if (final_cost < min_cost && flag)
      {
        min_cost = final_cost;
        best_speed[0] = i;
        best_speed[1] = j;
        trajectory = trajectoryTmp;
      }
      if (best_speed[0] < 0.001 && CState.speed < 0.001)
      {
        int left = 0;
        int right = 0;
        for (auto ob : temobs)
        {
          float dis = sqrt(pow(ob[0] - trajectory[trajectory.size() - 1].x, 2) +
                           pow(ob[1] - trajectory[trajectory.size() - 1].y, 2));
          if (dis > car.radius + 0.1)
          {
            continue;
          }
          // double ang = getAng(CState.x,CState.y, ob[0], ob[1],
          //       CState.yaw);
          double ang = getAng(trajectory[trajectory.size() - 1].x,
                              trajectory[trajectory.size() - 1].y, ob[0], ob[1],
                              CState.yaw);
          if (ang > 0)
          {
            left++;
          }
          else
          {
            right++;
          }
        }
        if (left >= right)
        {
          std::cout << "in left" << std::endl;
          best_speed[1] = -(car.max_angular_speed_rate * 0.5) * type;
        }
        else
        {
          std::cout << "in right" << std::endl;
          best_speed[1] = (car.max_angular_speed_rate * 0.5) * type;
        }
        std::cout << "*********" << std::endl;
      }
    }
  }
  cout << "best_speed:" << best_speed[0] << " , " << best_speed[1] << endl;
  bestSpeed = best_speed;
  nextpath.clear();
  for (auto nextpoint : trajectory)
  {
    nextpath.push_back(std::vector<float>{nextpoint.x, nextpoint.y});
  }

  return;
}

void DWA2::calcBestSpeed(
    const State &CState, const vector<float> &dw,
    std::queue<std::vector<std::vector<std::vector<float>>>> &obstacle,
    vector<float> &bestSpeed, std::vector<std::vector<float>> &nextpath,
    const int type)
{
  vector<float> best_speed{0, 0};
  vector<State> trajectoryTmp;
  vector<State> trajectory;
  float min_cost = 10000;
  float final_cost;
  float goal_cost;
  float speed_cost = 0;
  float obstacle_cost = 0;
  float distance_cost = 0;
  std::queue<std::vector<std::vector<std::vector<float>>>> temobs = obstacle;
  for (float i = dw[0]; i < dw[1]; i += car.v_resolution)
  {
    for (float j = dw[2]; j < dw[3]; j += car.yaw_rate_resolution)
    {
      //预测轨迹
      trajectoryTmp.clear();
      predictTrajectory(CState, i, j, trajectoryTmp, type);
      //计算代价
      goal_cost = car.goal_cost_gain * calcGoalCost(trajectoryTmp);
      speed_cost =
          car.speed_cost_gain * (car.max_speed - trajectoryTmp.back().speed);
      bool flag = true;
      obstacle_cost = car.obstacle_cost_gain *
                      calcObstacleCost(trajectoryTmp, obstacle, flag);
      distance_cost = car.dis_cost_gain *
                      sqrt(pow(destinationState.x - trajectoryTmp.back().x, 2) +
                           pow(destinationState.y - trajectoryTmp.back().y, 2));
      final_cost = goal_cost + speed_cost + obstacle_cost + distance_cost;

      if (final_cost < min_cost && flag)
      {
        min_cost = final_cost;
        best_speed[0] = i;
        best_speed[1] = j;
        trajectory = trajectoryTmp;
      }
      if (best_speed[0] < 0.001 && CState.speed < 0.001)
      {
        int left = 0;
        int right = 0;
        int queue_size = temobs.size();
        for (int i = 0; i < queue_size; i++)
        {
          std::vector<std::vector<std::vector<float>>> obsvec = temobs.front();
          temobs.push(obsvec);
          temobs.pop();
          for (auto obs : obsvec)
          {
            for (auto ob : obs)
            {
              float dis = sqrt(
                  pow(ob[0] - trajectoryTmp[trajectoryTmp.size() - 1].x, 2) +
                  pow(ob[1] - trajectoryTmp[trajectoryTmp.size() - 1].y, 2));
              if (dis > car.radius + 0.1)
              {
                continue;
              }

              // double ang = getAng(CState.x,CState.y, ob[0], ob[1],
              //        CState.yaw);
              double ang = getAng(trajectoryTmp[trajectoryTmp.size() - 1].x,
                                  trajectoryTmp[trajectoryTmp.size() - 1].y,
                                  ob[0], ob[1], CState.yaw);
              if (ang > 0)
              {
                left++;
              }
              else
              {
                right++;
              }
            }
          }
        }
        if (left >= right)
        {
          std::cout << "in left" << std::endl;
          best_speed[1] = -(car.max_angular_speed_rate * 0.8);
        }
        else
        {
          std::cout << "in right" << std::endl;
          best_speed[1] = (car.max_angular_speed_rate * 0.8);
        }
        std::cout << "xxxxxxxx" << std::endl;
      }
    }
  }
  cout << "best_speed:" << best_speed[0] << ",   " << best_speed[1] << endl;
  bestSpeed = best_speed;
  nextpath.clear();
  for (auto nextpoint : trajectory)
  {
    nextpath.push_back(std::vector<float>{nextpoint.x, nextpoint.y});
  }
  return;
}
// 在一段时间内预测轨迹
void DWA2::predictTrajectory(const State &CState, const float &speed,
                             const float &angular_speed,
                             vector<State> &trajectory, const int type)
{
  float time = 0;
  State nextState = CState;
  nextState.speed = speed;
  nextState.angular_speed = angular_speed;
  while (time < car.predict_time)
  {
    nextState = motionModel(nextState, speed, angular_speed, type);
    if (aaa)
      cout << "nextState:(" << nextState.x << ", " << nextState.y << ", "
           << nextState.yaw * 180 / PI << ")" << nextState.speed << "  "
           << nextState.angular_speed << endl;
    trajectory.push_back(nextState);
    time += car.dt;
  }
}

double DWA2::getAng(double now_x, double now_y, double tar_x, double tar_y,
                    double now_ang)
{
  double x = cos(now_ang) * (tar_x - now_x) + sin(now_ang) * (tar_y - now_y);
  double y = -sin(now_ang) * (tar_x - now_x) + cos(now_ang) * (tar_y - now_y);
  double ang = atan2(y, x);
  return ang;
  // var angle = 180 / Math.PI * radian; // 根据弧度计算角度
}
//根据动力学模型计算下一时刻状态
State DWA2::motionModel(const State &CState, const float &speed,
                        const float &angular_speed, const int type)
{
  State nextState;
  float nowx = CState.x;
  float nowy = CState.y;
  float nowang = nextState.yaw;
  nextState.x = CState.x + speed * car.dt * cos(CState.yaw);
  nextState.y = CState.y + speed * car.dt * sin(CState.yaw);
  nextState.yaw = CState.yaw + angular_speed * car.dt;

  nextState.speed = CState.speed;
  nextState.angular_speed = CState.angular_speed;
  return nextState;
}
// 计算方位角代价
float DWA2::calcGoalCost(const vector<State> &trajectory)
{
  float error_yaw = atan2(destinationState.y - trajectory.back().y,
                          destinationState.x - trajectory.back().x);
  float goal_cost = error_yaw - trajectory.back().yaw;
  //    cout << "error_yaw :" << error_yaw << "    yaw:" <<
  //    trajectory.back().yaw;
  goal_cost = atan2(sin(goal_cost), cos(goal_cost));
  //    cout << "    final:" << goal_cost << endl;
  if (goal_cost >= 0)
    return goal_cost;
  else
    return -goal_cost;
}

// 计算障碍代价
float DWA2::calcObstacleCost(const vector<State> &trajectory,
                             const std::vector<std::vector<float>> &obstacle,
                             bool &flag)
{
  float distance;
  for (auto obs : obstacle)
  {
    for (int j = 0; j < trajectory.size() - 1; j++)
    {
      distance = sqrt(pow(obs[0] - trajectory[j].x, 2) +
                      pow(obs[1] - trajectory[j].y, 2));
      if (distance <= car.radius)
      {
        flag = false;
        return 10000.0;
      }
    }
  }
  return 0;
  // return minDis;
}
float DWA2::calcObstacleCost(
    const vector<State> &trajectory,
    std::queue<std::vector<std::vector<std::vector<float>>>> &obstacle_,
    bool &flag)
{
  float distance;
  float minDis = FLT_MAX;
  while (!obstacle_.empty())
  {
    std::vector<std::vector<std::vector<float>>> obstacle = obstacle_.front();
    obstacle_.pop();
    for (auto obs1 : obstacle)
    {
      for (auto obs : obs1)
      {
        for (int j = 0; j < trajectory.size() - 1; j++)
        {
          distance = sqrt(pow(obs[0] - trajectory[j].x, 2) +
                          pow(obs[1] - trajectory[j].y, 2));
          if (distance <= car.radius)
          {
            flag = false;
            return 10000.0;
          }
        }
      }
    }
  }

  return 0;
}

int main(int argc, char const *argv[])
{
  dwa2->dwaControl(
      std::vector<float>{now_x, now_y, now_ang, control_opt[0], control_opt[1]},
      std::vector<float>{robot_x, robot_y}, obsBoxQueue, control_opt,
      trajectory_opt);
  return 0;
}

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

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

相关文章

【学习笔记】 科目一之概念篇

【学习笔记】 科目一之概念篇 概念题方法 1&#xff09;抓重点&#xff1a;科目一设计知识范围太广&#xff0c;不要妄想所有知识点都复习到&#xff0c;这是不可能的&#xff0c;我们的目标是45分几个而不是考高分&#xff0c;复习时间有限&#xff0c;所以要学会抓重点&…

图片是如何生成的--图像生成模型(GAN、VAE、扩散模型)简介

目录 1.GAN 2.AutoEncoder及其变种&#xff1a;AE/DAE/VAE/VQVAE 2.1 AE&#xff1a; 2.2 DAE&#xff1a;Denoising AutoEncoder 2.3 VAE&#xff1a;Variational AutoEncoder 2.4 VQVAE&#xff1a;Vector-quantised Variational AutoEncoder 3. 扩散模型 3.1 扩散…

【openGauss简单数据管理】--快速入门

【openGauss简单数据管理】--快速入门 &#x1f53b; 一、openGauss数据库管理&#x1f530; 1.1 连接openGauss数据库&#x1f530; 1.2 创建数据库&#x1f530; 1.3 查看数据库和切换数据库&#x1f530; 1.4 修改数据库&#x1f530; 1.5 删除数据库&#x1f530; 1.6 启停…

【QQ界面展示-实现自动回复 Objective-C语言】

一、刚才咱们监听键盘弹出事件,是怎么监听的, 1.监听键盘弹出事件的步骤 1)首先,在控制器的viewDidLoad方法中,创建一个NotificationCenter对象啊 2)通过center,让当前控制器的这个方法,监听这个通知, 3)然后,我们在这个通知里面,获取到键盘的Y值, 4)对我们的…

Rust 原始类型之数组array内置方法

目录 数组 array 声明 访问 引用 Reference 切片 Slice 方法 题目实例 数组 array 在 Rust 中&#xff0c;数组是一种固定大小的数据结构&#xff0c;用于存储具有相同数据类型的元素的有序集合。 “固定大小”是指数组中的元素的类型和数量确定&#xff0c;也就确定了…

【从零开始学习JAVA | 第十八篇】接口介绍

目录 前言&#xff1a; 接口&#xff1a; 如何定义一个接口&#xff1a; 如何使用一个接口&#xff1a; 接口中成员的特点&#xff1a; 接口与类的区别&#xff1a; 接口的应用&#xff1a; 总结&#xff1a; 前言&#xff1a; 接口其实是为了弥补继承的缺点&#xf…

C语言文件打开关闭详解、文件顺序读写详解。

文件的打开和关闭 fopen函数原型&#xff1a; FILE *fopen( const char *filename, const char *mode );const char *filename 文件的路径以及名字const char *mode 文件的打开方式 文件打开方式含义如果文件不存在“r”读文件不存在会报错“w”写(清空写)建立一个新的文件“…

【新手上路】如何在Web3时代成为XR创建者

目录 0 XR在Web3里的作用 1 XR的概念、特征、技术、设备、平台、应用和工具 1.1 VR的概念、特征和技术 1.2 AR的概念、特征和技术 1.2 XR的设备、平台、应用和工具 2 选择XR的方法 2.1 何时使用VR 2.2 何时使用AR 3 开发XR作品的4个步骤 4 成为XR构建者的路径 4.1 三…

小程序布局中相对定位的用法

小程序中一般为了有一定的设计效果&#xff0c;会将下边组件的内容提升一点到上边去&#xff0c;比如我们的电商展示模板里&#xff0c;会将商品列表覆盖一点到背景图&#xff0c;效果如下&#xff1a; 这种要如何搭建呢&#xff1f;就是利用到了CSS相对定位的原理 搭建组件 …

27.移除元素

LeetCode-27.移除元素 1、题目描述2、解题思路3、代码实现3.1Java代码实现3.2双指针代码优化 4、解题记录 1、题目描述 题目描述&#xff1a; 给你一个数组 nums 和一个值 val&#xff0c;你需要 原地 移除所有数值等于 val 的元素&#xff0c;并返回移除后数组的新长度。 不要…

windows搭建vue开发环境

参考博客&#xff1a;最详细的vue安装教程_一只野生程序媛的博客-CSDN博客 Vue安装环境最全教程&#xff0c;傻瓜式安装_浪漫主义码农的博客-CSDN博客 1、安装nodejs&#xff0c;从下面官网下载版本&#xff0c;对应安装就行了&#xff1a; Node.js 中文网 2、安装好后&…

合宙Air724UG Cat.1模块硬件设计指南--天线接口

天线接口 简介 天线是发射和接收电磁波的一个重要的无线电设备&#xff0c;没有天线也就没有无线电通信。天线品种繁多&#xff0c;以供不同频率、不同用途、不同场合、不同要求等不同情况下使用。 特性 LTE天线接口。50 欧姆特性阻抗&#xff0c;不推荐使用PCB板载天线&#…

脚本模式的特点和用法

一、什么是脚本? 脚本(script)是使用一种特定的描述性语言&#xff0c;依据一定的格式编写的可执行文件&#xff0c;又称作宏或批处理文件。脚本通常可以由应用程序临时调用并执行。 简单解释:脚本类似于演戏时用到的剧本&#xff0c;脚本其实就是一系列指令——演员看了指令就…

算法--itemCF

概述&#xff1a; 电子商务网站是个性化 推荐系统重要地应用的领域之一。亚马逊就是个性化推荐系统的积极应用者和推广者&#xff0c;亚马逊的推荐系统深入到网站的各类商品&#xff0c;为亚马逊带来了至少30%的销售额。 不光是电商类&#xff0c;推荐系统无处不在。 QQ&…

【差旅-游记】记一次海南出差

哈喽&#xff0c;大家好&#xff01;我是雷工&#xff01; 这篇不是技术分享&#xff0c;是篇差旅记录。 最近出差去了一次海南&#xff0c;应该算得上我目前出差去过最远的地方了&#xff0c;也是我第一次去海南&#xff0c;还是蛮有新鲜感的&#xff0c;因此记录下此次差旅。…

【软件设计师暴击考点】数据库系统高频考点暴击系列

&#x1f468;‍&#x1f4bb;个人主页&#xff1a;元宇宙-秩沅 &#x1f468;‍&#x1f4bb; hallo 欢迎 点赞&#x1f44d; 收藏⭐ 留言&#x1f4dd; 加关注✅! &#x1f468;‍&#x1f4bb; 本文由 秩沅 原创 &#x1f468;‍&#x1f4bb; 收录于专栏&#xff1a;软件…

tensorflow2 模型建立与训练

模型的构建&#xff1a; tf.keras.Model 和 tf.keras.layers 模型的损失函数&#xff1a; tf.keras.losses 模型的优化器&#xff1a; tf.keras.optimizer 模型的评估&#xff1a; tf.keras.metrics 模型&#xff08;Model&#xff09;与层&#xff08;Layer&#xff09; …

Mysql 索引基础介绍

索引基础介绍 索引是什么 MySQL官方&#xff1a;索引&#xff08;INDEX&#xff09;是帮助MySQL高效获取数据的数据结构。 面试官问&#xff0c;回&#xff1a;索引是排好序的快速查找数据结构 索引的目的在于提高查询效率&#xff0c;可以类比字典的目录。如果要查mysql这个这…

13. python从入门到精通——Python操作数据库

数据库编程接口&#xff1a;python database API python database API概述 python database API 规范对于关系数据库的访问&#xff0c;Python社区已经制定出一个标准&#xff0c;称为Python Database API&#xff0c;通过这个接口使python跨不同数据库的操作代码可以更加具有…

动态内存管理(malloc,calloc,realloc)

文章目录 1.为什么存在动态内存分配 2.动态内存函数的介绍 3.常见的动态内存错误 4.几个经典的笔试题 5. C/C程序的内存开辟 文章内容 1.为什么存在动态内存分配 我们已经掌握的内存开辟方式有&#xff1a; int val 20;//在栈空间上开辟四个字节 char arr[10] {0};/…