机器人局部动态避障算法dwa解析

2023-05-16

简介

dwa算法全称叫动态窗口法(dynamic window approach),其算法过程主要分为仿真获取机器人的运动轨迹、对轨迹进行评价选择最优轨迹两个主要过程,动态窗口表达的是仿真的运动轨迹数量有限,主要是因为机器人在较短的控制周期内只能达到一定的速度。
一、机器人如何仿真获取运动轨迹
1、获取机器人速度样本

根据机器人当前速度以及运动特性,确定机器人可达的运动速度范围。由于运动的最终目的是到达目标点,因此,在到达目标点附近时,需要降低机器人运动速度,也就是进一步限制机器人的速度范围,以保证机器人能平稳的到达目标点。最后根据人为给定的样本数,在限制的速度范围内获得样本数个离散的速度样本,包括线速度和角速度。

void SimpleTrajectoryGenerator::initialise(
const Eigen::Vector3f& pos, //机器人的位置
const Eigen::Vector3f& vel, //当前机器人速度
const Eigen::Vector3f& goal, //目标点
base_local_planner::LocalPlannerLimits* limits, //运动特性(加速度、最大最小速度…)
const Eigen::Vector3f& vsamples, //样本
bool discretize_by_time) {

//给定机器人的最大最小运动速度
double max_vel_th = limits->max_vel_theta;
double min_vel_th = -1.0 * max_vel_th;
discretize_by_time_ = discretize_by_time;
Eigen::Vector3f acc_lim = limits->getAccLimits();
pos_ = pos;
vel_ = vel;
limits_ = limits;
next_sample_index_ = 0;
sample_params_.clear();

double min_vel_x = limits->min_vel_x;
double max_vel_x = limits->max_vel_x;
double min_vel_y = limits->min_vel_y;
double max_vel_y = limits->max_vel_y;

// if sampling number is zero in any dimension, we don’t generate samples generically
if (vsamples[0] * vsamples[1] * vsamples[2] > 0) {
//compute the feasible velocity space based on the rate at which we run
Eigen::Vector3f max_vel = Eigen::Vector3f::Zero();
Eigen::Vector3f min_vel = Eigen::Vector3f::Zero();
if ( ! use_dwa_) {
//根据机器人位置到目标点的距离,限制机器人的最大运动速度
double dist = hypot(goal[0] - pos[0], goal[1] - pos[1]);
max_vel_x = std::max(std::min(max_vel_x, dist / sim_time_), min_vel_x);
max_vel_y = std::max(std::min(max_vel_y, dist / sim_time_), min_vel_y);
// 根据控制周期和加速度特性,确定机器人可达的最大最小速度
// 此处用的是sim_time_仿真时间,确定的是接下来一段时间内机器人可达的运动速度范围,默认是1s
max_vel[0] = std::min(max_vel_x, vel[0] + acc_lim[0] * sim_time_);
max_vel[1] = std::min(max_vel_y, vel[1] + acc_lim[1] * sim_time_);
max_vel[2] = std::min(max_vel_th, vel[2] + acc_lim[2] * sim_time_);
min_vel[0] = std::max(min_vel_x, vel[0] - acc_lim[0] * sim_time_);
min_vel[1] = std::max(min_vel_y, vel[1] - acc_lim[1] * sim_time_);
min_vel[2] = std::max(min_vel_th, vel[2] - acc_lim[2] * sim_time_);
} else {
// 此处用的sim_period_是控制周期,也就是只确定下一个控制周期机器人的运动速度范围
max_vel[0] = std::min(max_vel_x, vel[0] + acc_lim[0] * sim_period_);
max_vel[1] = std::min(max_vel_y, vel[1] + acc_lim[1] * sim_period_);
max_vel[2] = std::min(max_vel_th, vel[2] + acc_lim[2] * sim_period_);
min_vel[0] = std::max(min_vel_x, vel[0] - acc_lim[0] * sim_period_);
min_vel[1] = std::max(min_vel_y, vel[1] - acc_lim[1] * sim_period_);
min_vel[2] = std::max(min_vel_th, vel[2] - acc_lim[2] * sim_period_);
}
//根据给定的速度样本数,在速度空间内等间距的获取速度样本
Eigen::Vector3f vel_samp = Eigen::Vector3f::Zero();
VelocityIterator x_it(min_vel[0], max_vel[0], vsamples[0]);
VelocityIterator y_it(min_vel[1], max_vel[1], vsamples[1]);
VelocityIterator th_it(min_vel[2], max_vel[2], vsamples[2]);
for(; !x_it.isFinished(); x_it++) {
vel_samp[0] = x_it.getVelocity();
for(; !y_it.isFinished(); y_it++) {
vel_samp[1] = y_it.getVelocity();
for(; !th_it.isFinished(); th_it++) {
vel_samp[2] = th_it.getVelocity();
//ROS_DEBUG(“Sample %f, %f, %f”, vel_samp[0], vel_samp[1], vel_samp[2]);
sample_params_.push_back(vel_samp);
}
th_it.reset();
}
y_it.reset();
}
}
}

2、生成运动轨迹

根据速度样本确定运动轨迹,是简单运行学知识,主要注意的是用的仿真时间产生的样本还是仿真周期产生的样本,其中仿真时间指的是人为设定的一段仿真时间,默认1秒,而仿真周期指的是算法的实际控制周期,默认为0.1秒。

bool SimpleTrajectoryGenerator::generateTrajectory(
Eigen::Vector3f pos, //机器人的位姿
Eigen::Vector3f vel, //运动速度
Eigen::Vector3f sample_target_vel, //样本速度
base_local_planner::Trajectory& traj) { //需要生成的轨迹
double vmag = hypot(sample_target_vel[0], sample_target_vel[1]);
double eps = 1e-4;
traj.cost_ = -1.0; // placed here in case we return early
//trajectory might be reused so we’ll make sure to reset it
traj.resetPoints();

//确定样本是否超过设定的最大移动速度
// make sure that the robot would at least be moving with one of
// the required minimum velocities for translation and rotation (if set)
if ((limits_->min_vel_trans >= 0 && vmag + eps < limits_->min_vel_trans) &&
(limits_->min_vel_theta >= 0 && fabs(sample_target_vel[2]) + eps < limits_->min_vel_theta)) {
return false;
}
// make sure we do not exceed max diagonal (x+y) translational velocity (if set)
if (limits_->max_vel_trans >=0 && vmag - eps > limits_->max_vel_trans) {
return false;
}

//确定仿真使用的控制周期数
int num_steps;
if (discretize_by_time_) {
num_steps = ceil(sim_time_ / sim_granularity_);
} else {
//compute the number of steps we must take along this trajectory to be “safe”
double sim_time_distance = vmag * sim_time_; // the distance the robot would travel in sim_time if it did not change velocity
double sim_time_angle = fabs(sample_target_vel[2]) * sim_time_; // the angle the robot would rotate in sim_time
num_steps =
ceil(std::max(sim_time_distance / sim_granularity_,
sim_time_angle / angular_sim_granularity_));
}

if (num_steps == 0) {
return false;
}

//确定生成轨迹的时间间隔(仅对利用仿真时间进行速度采样的情况)
//compute a timestep
double dt = sim_time_ / num_steps;
traj.time_delta_ = dt;

Eigen::Vector3f loop_vel;
//连续加速意味着用的是仿真时间进行的速度采样,不是单个控制周期能达到的运动速度。因此,需要根据机器人的运动特性确定接下来的控制周期内机器人能达到的运动速度
if (continued_acceleration_) {
// assuming the velocity of the first cycle is the one we want to store in the trajectory object
loop_vel = computeNewVelocities(sample_target_vel, vel, limits_->getAccLimits(), dt);
traj.xv_ = loop_vel[0];
traj.yv_ = loop_vel[1];
traj.thetav_ = loop_vel[2];
} else {
//否则用的就是仿真周期进行的采样,直接将采样速度作为生成轨迹的速度
// assuming sample_vel is our target velocity within acc limits for one timestep
loop_vel = sample_target_vel;
traj.xv_ = sample_target_vel[0];
traj.yv_ = sample_target_vel[1];
traj.thetav_ = sample_target_vel[2];
}

//根据仿真的周期数,生成仿真轨迹
for (int i = 0; i < num_steps; ++i) {
//add the point to the trajectory so we can draw it later if we want
traj.addPoint(pos[0], pos[1], pos[2]);
//如果用的是仿真时间进行的速度采样,在每个仿真控制周期内,速度需要根据加减速特性确定
if (continued_acceleration_) {
//calculate velocities
loop_vel = computeNewVelocities(sample_target_vel, loop_vel, limits_->getAccLimits(), dt);
//ROS_WARN_NAMED(“Generator”, “Flag: %d, Loop_Vel %f, %f, %f”, continued_acceleration_, loop_vel[0], loop_vel[1], loop_vel[2]);
}
//根据速度和时间,确定运动轨迹上的下一个点
//update the position of the robot using the velocities passed in
pos = computeNewPositions(pos, loop_vel, dt);

} // end for simulation steps

return true; // trajectory has at least one point
}

二、如何对轨迹进行评价并选取最优轨迹
1、代价函数

oscillation_costs_ //振荡代价函数,一旦速度发生振荡,直接丢弃速度样本
obstacle_costs_ //障碍物代价函数,当轨迹进入障碍物区,直接丢弃当前轨迹样本
goal_costs_ //目标代价函数,优先选择距离局部目标点近的轨迹
path_costs_ //路径代价函数,优先选择贴近全局路径的轨迹
goal_front_costs_ //与goal_costs基本一致,不太理解注释中的nose是指什么?
alignment_costs_ //与path_costs基本一致,不太理解注释中的nose是指什么?
  注:为了能适应不同场景的需求,可以对这些代价函数配置不同的权重,从而能实现不同场景对这些代价函数的重视程度
2、主要评价函数的实现
2.1、障碍物代价函数

通过仿真轨迹将机器人轮廓映射到全局坐标系下,并对轮廓边上的代价值进行分析,选择最大的代价值作为障碍物代价,从而确定机器人是否会撞到障碍物

double CostmapModel::footprintCost(const geometry_msgs::Point& position, //机器人在全局坐标系下的位置
const std::vector<geometry_msgs::Point>& footprint, //机器人轮廓
double inscribed_radius, double circumscribed_radius) //内切圆、外接圆半径
{
//used to put things into grid coordinates
unsigned int cell_x, cell_y;
//get the cell coord of the center point of the robot
//获得机器人在地图坐标系下的坐标
if(!costmap_.worldToMap(position.x, position.y, cell_x, cell_y))
return -1.0;
//if number of points in the footprint is less than 3, we’ll just assume a circular robot
//当轮廓上的点数少于3时,认为机器人是个圆形机器人,并且只判断机器人中心是否在不可走区域
if(footprint.size() < 3){
unsigned char cost = costmap_.getCost(cell_x, cell_y);
//if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE)
if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION)
return -1.0;
return cost;
}
//now we really have to lay down the footprint in the costmap grid
unsigned int x0, x1, y0, y1;
double line_cost = 0.0;
double footprint_cost = 0.0;
//footprint是一个多边形,判断该多边形是否与障碍物发生碰撞的方法是:计算多边形的所有边的最大代价值,从而确定是否与障碍物相撞
//we need to rasterize each line in the footprint
for(unsigned int i = 0; i < footprint.size() - 1; ++i){
//get the cell coord of the first point
//获得地图中机器人轮廓上的一个点的坐标
if(!costmap_.worldToMap(footprint[i].x, footprint[i].y, x0, y0))
return -1.0;
//获得地图中相邻轮廓点的坐标
//get the cell coord of the second point
if(!costmap_.worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1))
return -1.0;
//确定当前轮廓点与相邻轮廓点构成的边的最大代价值
line_cost = lineCost(x0, x1, y0, y1);
//选取所有边的最大代价值
footprint_cost = std::max(line_cost, footprint_cost);
//if there is an obstacle that hits the line… we know that we can return false right away
if(line_cost < 0)
return -1.0;
}
//获取第一个轮廓点与最后一个轮廓点构成的边的最大代价值
//we also need to connect the first point in the footprint to the last point
//get the cell coord of the last point
if(!costmap_.worldToMap(footprint.back().x, footprint.back().y, x0, y0))
return -1.0;
//get the cell coord of the first point
if(!costmap_.worldToMap(footprint.front().x, footprint.front().y, x1, y1))
return -1.0;
line_cost = lineCost(x0, x1, y0, y1);
//确定所有边的最大代价值
footprint_cost = std::max(line_cost, footprint_cost);
if(line_cost < 0)
return -1.0;
//if all line costs are legal… then we can return that the footprint is legal
return footprint_cost;

}

2.2、目标代价函数

首先根据全局路径与局部代价地图的边界确定局部目标点,然后依据局部目标点生成栅格地图,每个栅格处的值代表当前栅格到目标点的距离,对于障碍物栅格,直接置为到目标点的距离无穷远。最后再根据轨迹末端点处栅格的位置,直接通过索引在地图中获取该位置距目标点的距离,作为距目标点的代价。因此,目标代价函数的主要任务是生成栅格地图。

//mark the point of the costmap as local goal where global_plan first leaves the area (or its last point)
void MapGrid::setLocalGoal(const costmap_2d::Costmap2D& costmap, //局部代价地图
const std::vector<geometry_msgs::PoseStamped>& global_plan)  //全局路径
{
sizeCheck(costmap.getSizeInCellsX(), costmap.getSizeInCellsY());
int local_goal_x = -1;
int local_goal_y = -1;
bool started_path = false;
//调整全局路径分辨率与地图分辨率一致
std::vector<geometry_msgs::PoseStamped> adjusted_global_plan;
adjustPlanResolution(global_plan, adjusted_global_plan, costmap.getResolution());
// 将全局路径与局部代价地图边界的交点作为局部目标点
for (unsigned int i = 0; i < adjusted_global_plan.size(); ++i) {
double g_x = adjusted_global_plan[i].pose.position.x;
double g_y = adjusted_global_plan[i].pose.position.y;
unsigned int map_x, map_y;
if (costmap.worldToMap(g_x, g_y, map_x, map_y) && costmap.getCost(map_x, map_y) != costmap_2d::NO_INFORMATION) {
local_goal_x = map_x;
local_goal_y = map_y;
started_path = true;
} else {
if (started_path) {
break;
}// else we might have a non pruned path, so we just continue
}
}
if (!started_path) {
ROS_ERROR(“None of the points of the global plan were in the local costmap, global plan points too far from robot”);
return;
}
//构建距离优先队列,并添加局部目标点作为队列的第一个点
queue<MapCell*> path_dist_queue;
if (local_goal_x >= 0 && local_goal_y >= 0) {
MapCell& current = getCell(local_goal_x, local_goal_y);
costmap.mapToWorld(local_goal_x, local_goal_y, goal_x_, goal_y_);
current.target_dist = 0.0;
current.target_mark = true;
path_dist_queue.push(&current);
}
//按优先队列的顺序,从局部目标点开始以单个栅格为步长向外膨胀,从而直接确定出每个栅格距离局部目标点的距离
computeTargetDistance(path_dist_queue, costmap);
}

2.3、路径代价函数

该代价函数的实现原理与目标代价函数类似,只是该函数是以局部路径上的所有点作为起点向外膨胀来构建栅格地图,并且是以仿真轨迹上的所有点的距离值的和的平均值作为轨迹的代价值。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

机器人局部动态避障算法dwa解析 的相关文章

  • rt-thread应用篇(03)---基于STM32F429实现web服务器功能

    目录 参考示例 前言 一 需使用的组件与软件包及其ENV配置 1 文件系统相关组件与软件包 1 1 DFS 框架 1 2 fal 软件包 1 3 SFUD 组件 2 网络通信相关组件和软件包 2 1 SAL组件 2 2 netdev组件 2
  • rt-thread的at组件在freeRTOS上的移植与应用

    目录 一 AT命令 二 rtthread at组件简介 三 移植到freeRTOS 3 1 数据结构 3 2 API 3 3 at client 流程 3 4 串口数据接收处理 3 5 数据缓存 顺序队列 四 使用示例 4 1 串口配置信息
  • rt-thread驱动篇(04)---STM32F429单片机模拟SPI FLASH驱动添加

    目录 一 添加驱动 1 新增模拟SPI驱动文件 drv soft spi c h 2 新增模拟SPI配置文件 soft spi config h 二 向工程添加文件 1 修改 board Kconfig 2 修改 rt thread com
  • RT-Thread实时操作系统简介

    目录 一 概述 二 架构 三 版本选择 四 内核启动流程 五 自动初始化机制 六 内核对象模型 七 I O设备模型 1 框架 2 设备驱动使用序列图 3 设备类型 八 FinSH控制台 九 ENV工具 1 menuconfig 2 Scon
  • Altium Allegro PADS到底该选哪个EDA设计软件

    废话少说 xff0c 就像之前 学好数理化 xff0c 走遍天下都不怕 一样 xff0c 在如今快速发展的电子时代 xff0c 掌握一门电子设计EDA软件工具 xff0c 在职场上真的走遍天下都不怕 哪哪都有可能跟电沾边 xff0c 跟控制
  • QML学习笔记【07】:QML访问复杂组件的子项

    1 访问复杂组件的子项 gt Row Column Grid Flow布局子项或Repeater子项 访问复杂组件的子项 gt Row Column Grid Flow布局子项或Repeater子项 Window width 640 hei
  • tslib-1.4在I.MX6ULL开发板上电容屏不能触摸问题

    一 前言 在采用触摸屏的移动终端中 xff0c 触摸屏性能的调试是个重要问题之一 xff0c 因为电磁噪声的缘故 xff0c 触摸屏容易存在点击不准确 有抖动等问题 Tslib是一个开源的程序 xff0c 能够为触摸屏驱动获得的采样提供诸如
  • C++与QML混合编程

    一 前言 简单来说 xff0c 混合编程就是通过Qml高效便捷的构建UI界面 xff0c 而使用C 43 43 来实现业务逻辑和复杂算法 Qt集成了QML引擎和Qt元对象系统 xff0c 使得QML很容易从C 43 43 中得到扩展 xff
  • 卸载ROS功能包

    步骤方法 xff1a 1 首先卸载包 sudo apt get purge ros indigo 2 然后卸载依赖包 sudo apt get autoremove
  • 要点初见:通过ROS包nmea_navsat_driver读取GPS、北斗定位信息(C/C++)

    先前在树莓派上用C C 43 43 读取过GPS北斗双模定位模块 xff0c 但因为定位模块的若干条定位数据无法立刻读取 xff0c 需要用delay 延迟1到2秒的时间才能把所有定位数据都读取进程序 xff0c 又不想写多线程 xff0c
  • 自动驾驶-使用卡尔曼滤波算法定位和跟踪

    参加过科一的人都知道 xff0c 学车的第一步不是操控车辆而是遵守交规 xff0c 行车礼让 xff0c 确保安全 可见安全驾驶才是行车的第一原则 为了确保安全 xff0c 司机应该观察周围车辆和行人的位置 xff0c 保持安全距离 自动驾
  • ROS使用笔记

    文章目录 1 提取bag中固定topic或者固定时间段数据2 提取pcd数据3 记录数据4 service amp action5 roslaunch文件6 自定义消息7 from raw velodyne packets to velod
  • linux安装Android Studio

    linux安装Android Studio 1 先在https developer android google cn studio hl 61 zh cn下载源码安装包 2 安装64位所需要的库 2 1如果使用的是Ubuntu的话执行以下
  • OpenCV中Mat的初始化与赋值

    1 type数据类型 常量类型的命名规则为 xff1a CV 位数 43 数据类型 43 通道数 关系如下 xff1a C1 C2 C3 C4 CV 8U 0 8 16 24 CV 8S 1 9 17 25 CV 16U 2 10 18 2

随机推荐

  • 近十年的VI-SLAM算法综述与发展

    本文主要总结一下这几年工作中遇到过以及改进过相关VIO算法 1 背景介绍 一个完整的 SLAM simultaneous localization and mapping 框架包括传感器数据 前端 后端 回环检测与建图 xff0c 如图1所
  • 当前开源的SLAM方案汇总2021.02

    感谢SLAMer前辈们不断的拼搏与进取 xff0c 才有了现在的丰富的学习资料 xff01 以下是至今SLAM开源代码的资料汇总 xff0c 后续将会更新主流slam开源代码的注释版本 xff0c 希望对研究SLAM的同学们有帮助 PTAM
  • VSLAM算法中的数学基础知识详细了解

    学习SLAM经验告诉我 xff0c 入门SLAM一般只需要两种两个方面的条件 xff0c 一是要有扎实的数学基础 xff0c 二是要有强大的动手编程能力 xff0c 但是这两个条件对于刚入门的同学来说 xff0c 极具挑战性 学习SLAM的
  • 2021互联网大厂职级对应薪资一览表

    原文连接 xff1a https mp weixin qq com s nYNZjJJzrO0Sc5h2AEPnaQ 互联网大厂新入职员工各职级薪资对应表 xff08 技术线 xff09 图片数据来源 xff1a 知乎加 上面的表格不排除有
  • “undefined reference to“ 问题及解决方法 实例分析

    在实际编译代码的过程中 xff0c 我们经常会遇到 34 undefined reference to 34 的问题 xff0c 简单的可以轻易地解决 xff0c 但有些却隐藏得很深 xff0c 需要花费大量的时间去排查 工作中遇到了各色各
  • int 占几个字节

    4个字节或2个字节 xff0c 主要看操作系统 xff0c 和编译器有关 xff0c 一个int的大小是操作系统的一个字长 TC是16位系统程序 xff0c 所以int是16bit xff0c 也就是两个字节 在32位linux和32位或6
  • ORBSLAM3 VIO初始化

    按照规矩 xff0c 先讲一下ORBSLAM3中的初始化大致流程 根据ORB SLAM3的论文介绍 xff0c IMU的初始化方法是基于下面3点 xff1a 1 xff09 纯视觉SLAM可以提供很好的位姿估计 xff0c 所以可以用纯视觉
  • 不一样的静态初始化——OpenVins

    今天讲一下黄国权老师实验室开源的OpenVins工程中的IMU初始化 xff0c 一般VIO初始化分为两种 xff0c 一种是静态初始化 xff0c 一种是动态初始化 xff0c 而OpenVins则利用加速度的方差差异将运动分为两种状态
  • CMakeList.txt的指令以及实例介绍

    一 Cmake 简介 cmake xff08 Cross platform make xff09 是一个开源的跨平台自动化构建系统 xff0c 用来管理程序构建 xff0c 不依于特定的编译器 所谓的跨平台就是可以在Windows xff0
  • 语法错误( error: array bound is not an integer constant before ‘]’ token)

    include lt iostream gt include lt cstdio gt using namespace std int N 61 100 int a N N int main 编译出现了 Error array bound
  • 使用ADB出现了system/bin/sh: adb: not found&system/bin/sh: pull: not found错误

    在使用ADB传送文件的时候出现了system bin sh adb not found amp system bin sh pull not found错误 解决办法 xff1a 可能你在使用adb pull 之前你使用了adb shell
  • 回环检测之决策模型

    前面我们已经讲了如何描述场景 xff0c 让机器人尽可能的了解周围环境 xff0c 那么了解了之后 xff0c 如何判断出是回环的呢 xff1f 本节讨论如何建立决策模型来根据当前场景描述和地图信息识别出可能的闭环 合理的决策模型可有效提高
  • 回环检测之DBoW2

    前面我们已经讲了回环检测中用的一些方法 xff0c 今天主要介绍一下现在用的最多的词袋模型 DBoW2 这里就不在细讲回环检测的定义 xff0c 具体可以看看我的前面的博客 xff0c 而回环检测在SLAM中的作用可以从下面的图片中大致有一
  • 快速解决rosdep update一直不通过问题

    以前安装ROS的时候遇到rosdep update不通过 xff0c 需要很多次测试才能通过 xff0c 能通过完全靠运气 xff0c 也找了网上很多种方法 xff0c 比较麻烦 xff0c 今天这里说一下一位大神帅鱼提供的一个方法 xff
  • Matlab读取文本数据

    用Nastran的时候 xff0c 想把bdf文件里的节点坐标导出来 xff0c 但是坐标的格式很奇怪 xff0c 见下图 xff1a 会发现这种科学计数法中间没有字母E或e xff0c 直接用Matlab中的load函数读取的话 xff0
  • 为学弟学妹熬夜的一份零基础 C++ 开发学习路线

    大家好 xff0c 我是帅地 之前写过几篇学习路线的文章 前端开发学习路线 Java 后端开发学习路线 一般开发岗主流的就是 Java 后台开发 xff0c 前端开发以及 C 43 43 后台开发 xff0c 现在 Go 开发也是越来越多了
  • ars408_ros驱动问题

    0 ars408 ros驱动 mkdir folder mkdir folder src cd folder src git clone https github com sergiocasaspastor myrepository git
  • Tensorflow实战:LSTM原理及实现(详解)

    LSTM规避了标准RNN中梯度爆炸和梯度消失的问题 xff0c 所以会显得更好用 xff0c 学习速度更快 下图是最基本的LSTM单元连接起来的样子 上图为一层LSTM单元连接起来的样子 xff0c 在工业上 xff0c LSTM是可以像一
  • Gazebo版本升级7.0--->7.16

    GPU issues The GPU problems reported in this issue have been solved with this pull request for the gazebo7branch The Gaz
  • 机器人局部动态避障算法dwa解析

    简介 dwa算法全称叫动态窗口法 xff08 dynamic window approach xff09 xff0c 其算法过程主要分为仿真获取机器人的运动轨迹 对轨迹进行评价选择最优轨迹两个主要过程 xff0c 动态窗口表达的是仿真的运动