当前位置: 首页 > news >正文

ROS2机器人编程简述humble-第四章-BASIC DETECTOR .3

书中程序适用于turtlebot、husky等多种机器人,配置相似都可以用的。

支持ROS2版本foxy、humble。

基础检测效果如下:

由于缺¥,所有设备都非常老旧,都是其他实验室淘汰或者拼凑出来的设备。机器人控制笔记本是2010年版本。

但是依然可以跑ROS1、ROS2。

book_ros2/br2_tf2_detector目录:

.
├── CMakeLists.txt
├── include
│   └── br2_tf2_detector
│       ├── ObstacleDetectorImprovedNode.hpp
│       ├── ObstacleDetectorNode.hpp
│       └── ObstacleMonitorNode.hpp
├── launch
│   ├── detector_basic.launch.py
│   ├── detector_improved.launch.py
│   ├── turtlebot_detector_basic.launch.py
│   └── turtlebot_detector_improved.launch.py
├── package.xml
└── src├── br2_tf2_detector│   ├── ObstacleDetectorImprovedNode.cpp│   ├── ObstacleDetectorNode.cpp│   ├── ObstacleMonitorNode (copy).cpp│   └── ObstacleMonitorNode.cpp├── detector_improved_main.cpp└── detector_main.cpp5 directories, 15 files

里面有两个部分basic和improved。

CMakelist(lib):

cmake_minimum_required(VERSION 3.5)
project(br2_tf2_detector)set(CMAKE_CXX_STANDARD 17)# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)set(dependenciesrclcpptf2_rosgeometry_msgssensor_msgsvisualization_msgs
)include_directories(include)add_library(${PROJECT_NAME} SHAREDsrc/br2_tf2_detector/ObstacleDetectorNode.cppsrc/br2_tf2_detector/ObstacleMonitorNode.cppsrc/br2_tf2_detector/ObstacleDetectorImprovedNode.cpp
)
ament_target_dependencies(${PROJECT_NAME} ${dependencies})add_executable(detector src/detector_main.cpp)
ament_target_dependencies(detector ${dependencies})
target_link_libraries(detector ${PROJECT_NAME})add_executable(detector_improved src/detector_improved_main.cpp)
ament_target_dependencies(detector_improved ${dependencies})
target_link_libraries(detector_improved ${PROJECT_NAME})install(TARGETS${PROJECT_NAME}detectordetector_improvedARCHIVE DESTINATION libLIBRARY DESTINATION libRUNTIME DESTINATION lib/${PROJECT_NAME}
)install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})if(BUILD_TESTING)find_package(ament_lint_auto REQUIRED)ament_lint_auto_find_test_dependencies()
endif()ament_package()

障碍物识别节点

// Copyright 2021 Intelligent Robotics Lab
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.#include <memory>#include "br2_tf2_detector/ObstacleDetectorNode.hpp"#include "sensor_msgs/msg/laser_scan.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"#include "rclcpp/rclcpp.hpp"namespace br2_tf2_detector
{using std::placeholders::_1;ObstacleDetectorNode::ObstacleDetectorNode()
: Node("obstacle_detector")
{scan_sub_ = create_subscription<sensor_msgs::msg::LaserScan>("input_scan", rclcpp::SensorDataQoS(),std::bind(&ObstacleDetectorNode::scan_callback, this, _1));tf_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(*this);
}void
ObstacleDetectorNode::scan_callback(sensor_msgs::msg::LaserScan::UniquePtr msg)
{double dist = msg->ranges[msg->ranges.size() / 2];if (!std::isinf(dist)) {geometry_msgs::msg::TransformStamped detection_tf;detection_tf.header = msg->header;detection_tf.child_frame_id = "detected_obstacle";detection_tf.transform.translation.x = msg->ranges[msg->ranges.size() / 2];tf_broadcaster_->sendTransform(detection_tf);}
}}  // namespace br2_tf2_detector

主要就是回调函数完成大部分功能。具体参考源代码即可。

障碍物监控节点:

// Copyright 2021 Intelligent Robotics Lab
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.#include <tf2/transform_datatypes.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>#include <memory>#include "br2_tf2_detector/ObstacleMonitorNode.hpp"#include "geometry_msgs/msg/transform_stamped.hpp"#include "rclcpp/rclcpp.hpp"namespace br2_tf2_detector
{using namespace std::chrono_literals;ObstacleMonitorNode::ObstacleMonitorNode()
: Node("obstacle_monitor"),tf_buffer_(),tf_listener_(tf_buffer_)
{marker_pub_ = create_publisher<visualization_msgs::msg::Marker>("obstacle_marker", 1);timer_ = create_wall_timer(500ms, std::bind(&ObstacleMonitorNode::control_cycle, this));
}void
ObstacleMonitorNode::control_cycle()
{geometry_msgs::msg::TransformStamped robot2obstacle;try {robot2obstacle = tf_buffer_.lookupTransform("odom", "detected_obstacle", tf2::TimePointZero);} catch (tf2::TransformException & ex) {RCLCPP_WARN(get_logger(), "Obstacle transform not found: %s", ex.what());return;}double x = robot2obstacle.transform.translation.x;double y = robot2obstacle.transform.translation.y;double z = robot2obstacle.transform.translation.z;double theta = atan2(y, x);RCLCPP_INFO(get_logger(), "Obstacle detected at (%lf m, %lf m, , %lf m) = %lf rads",x, y, z, theta);visualization_msgs::msg::Marker obstacle_arrow;obstacle_arrow.header.frame_id = "odom";obstacle_arrow.header.stamp = now();obstacle_arrow.type = visualization_msgs::msg::Marker::ARROW;obstacle_arrow.action = visualization_msgs::msg::Marker::ADD;obstacle_arrow.lifetime = rclcpp::Duration(1s);geometry_msgs::msg::Point start;start.x = 0.0;start.y = 0.0;start.z = 0.0;geometry_msgs::msg::Point end;end.x = x;end.y = y;end.z = z;obstacle_arrow.points = {start, end};obstacle_arrow.color.r = 1.0;obstacle_arrow.color.g = 0.0;obstacle_arrow.color.b = 0.0;obstacle_arrow.color.a = 1.0;obstacle_arrow.scale.x = 0.02;obstacle_arrow.scale.y = 0.1;obstacle_arrow.scale.z = 0.1;marker_pub_->publish(obstacle_arrow);
}}  // namespace br2_tf2_detector

代码和原始版本稍微有些不同。

重要部分:

  try {robot2obstacle = tf_buffer_.lookupTransform("odom", "detected_obstacle", tf2::TimePointZero);} catch (tf2::TransformException & ex) {RCLCPP_WARN(get_logger(), "Obstacle transform not found: %s", ex.what());return;}double x = robot2obstacle.transform.translation.x;double y = robot2obstacle.transform.translation.y;double z = robot2obstacle.transform.translation.z;double theta = atan2(y, x);RCLCPP_INFO(get_logger(), "Obstacle detected at (%lf m, %lf m, , %lf m) = %lf rads",x, y, z, theta);

如果tf不能正常工作,会报错Obstacle transform not found:

例如odom没有

[detector-1] [WARN] [1676266943.177279939] [obstacle_monitor]: Obstacle transform not found: "odom" passed to lookupTransform argument target_frame does not exist.

例如detected_obstacle没有

[detector-1] [WARN] [1676267019.166991316] [obstacle_monitor]: Obstacle transform not found: "detected_obstacle" passed to lookupTransform argument source_frame does not exist. 

需要思考并解决问题哦^_^

如果都ok!那么"Obstacle detected at (%lf m, %lf m, , %lf m) = %lf rads":

机器人在运动中所以角度和距离会不断变化。

此时如果查看:

rqt

其中检测tf是由激光传感器测距给出的。

节点主题图:

这个代码主程序!

// Copyright 2021 Intelligent Robotics Lab
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.#include <memory>#include "br2_tf2_detector/ObstacleDetectorNode.hpp"
#include "br2_tf2_detector/ObstacleMonitorNode.hpp"#include "rclcpp/rclcpp.hpp"int main(int argc, char * argv[])
{rclcpp::init(argc, argv);auto obstacle_detector = std::make_shared<br2_tf2_detector::ObstacleDetectorNode>();auto obstacle_monitor = std::make_shared<br2_tf2_detector::ObstacleMonitorNode>();rclcpp::executors::SingleThreadedExecutor executor;executor.add_node(obstacle_detector->get_node_base_interface());executor.add_node(obstacle_monitor->get_node_base_interface());executor.spin();rclcpp::shutdown();return 0;
}

这里需要注意!

  rclcpp::executors::SingleThreadedExecutor executor;executor.add_node(obstacle_detector->get_node_base_interface());executor.add_node(obstacle_monitor->get_node_base_interface());

如果C++掌握一般推荐看一看:

蓝桥ROS机器人之现代C++学习笔记7.1 并行基础

多线程是如何实现的。

整个程序要跑起来:

终端1-gazebo仿真:ros2 launch turtlebot3_gazebo empty_world.launch.py

ros2 launch turtlebot3_gazebo empty_world.launch.py 
[INFO] [launch]: All log files can be found below /home/zhangrelay/.ros/log/2023-02-13-13-43-10-244500-Aspire4741-10860
[INFO] [launch]: Default logging verbosity is set to INFO
urdf_file_name : turtlebot3_burger.urdf
[INFO] [gzserver-1]: process started with pid [10862]
[INFO] [gzclient   -2]: process started with pid [10864]
[INFO] [ros2-3]: process started with pid [10868]
[INFO] [robot_state_publisher-4]: process started with pid [10870]
[robot_state_publisher-4] [WARN] [1676266991.467830827] [robot_state_publisher]: No robot_description parameter, but command-line argument available.  Assuming argument is name of URDF file.  This backwards compatibility fallback will be removed in the future.
[robot_state_publisher-4] Parsing robot urdf xml string.
[robot_state_publisher-4] Link base_link had 5 children
[robot_state_publisher-4] Link caster_back_link had 0 children
[robot_state_publisher-4] Link imu_link had 0 children
[robot_state_publisher-4] Link base_scan had 0 children
[robot_state_publisher-4] Link wheel_left_link had 0 children
[robot_state_publisher-4] Link wheel_right_link had 0 children
[robot_state_publisher-4] [INFO] [1676266991.472337172] [robot_state_publisher]: got segment base_footprint
[robot_state_publisher-4] [INFO] [1676266991.472419811] [robot_state_publisher]: got segment base_link
[robot_state_publisher-4] [INFO] [1676266991.472444636] [robot_state_publisher]: got segment base_scan
[robot_state_publisher-4] [INFO] [1676266991.472465018] [robot_state_publisher]: got segment caster_back_link
[robot_state_publisher-4] [INFO] [1676266991.472485972] [robot_state_publisher]: got segment imu_link
[robot_state_publisher-4] [INFO] [1676266991.472505808] [robot_state_publisher]: got segment wheel_left_link
[robot_state_publisher-4] [INFO] [1676266991.472525491] [robot_state_publisher]: got segment wheel_right_link
[ros2-3] Set parameter successful
[INFO] [ros2-3]: process has finished cleanly [pid 10868]
[gzserver-1] [INFO] [1676266994.292818234] [turtlebot3_imu]: <initial_orientation_as_reference> is unset, using default value of false to comply with REP 145 (world as orientation reference)
[gzserver-1] [INFO] [1676266994.417396256] [turtlebot3_diff_drive]: Wheel pair 1 separation set to [0.160000m]
[gzserver-1] [INFO] [1676266994.417528534] [turtlebot3_diff_drive]: Wheel pair 1 diameter set to [0.066000m]
[gzserver-1] [INFO] [1676266994.420616206] [turtlebot3_diff_drive]: Subscribed to [/cmd_vel]
[gzserver-1] [INFO] [1676266994.425994254] [turtlebot3_diff_drive]: Advertise odometry on [/odom]
[gzserver-1] [INFO] [1676266994.428920116] [turtlebot3_diff_drive]: Publishing odom transforms between [odom] and [base_footprint]
[gzserver-1] [INFO] [1676266994.460852885] [turtlebot3_joint_state]: Going to publish joint [wheel_left_joint]
[gzserver-1] [INFO] [1676266994.461009035] [turtlebot3_joint_state]: Going to publish joint [wheel_right_joint]

终端2-障碍物检测:

ros2 launch br2_tf2_detector turtlebot_detector_basic.launch.py

终端3-rqt:rqt

终端4-rviz2:rviz2

windows端也可以获取信息。

补充:

四元数是方向的4元组表示,它比旋转矩阵更简洁。四元数对于分析涉及三维旋转的情况非常有效。四元数广泛应用于机器人、量子力学、计算机视觉和3D动画。

可以在维基百科上了解更多关于基础数学概念的信息。还可以观看一个可探索的视频系列,将3blue1brown制作的四元数可视化。

官方教程将指导完成调试典型tf2问题的步骤。它还将使用许多tf2调试工具,如tf2_echo、tf2_monitor和view_frames。

TF2完整教程提纲:

tf2

许多tf2教程都适用于C++和Python。这些教程经过简化,可以完成C++曲目或Python曲目。如果想同时学习C++和Python,应该学习一次C++教程和一次Python教程。

目录

工作区设置

学习tf2

调试tf2

将传感器消息与tf2一起使用

工作区设置

如果尚未创建完成教程的工作空间,请遵循本教程。

学习tf2

tf2简介。

本教程将让了解tf2可以为您做什么。它在一个多机器人的例子中展示了一些tf2的力量,该例子使用了turtlesim。这还介绍了使用tf2_echo、view_frames和rviz。

编写静态广播(Python)(C++)。

本教程教如何向tf2广播静态坐标帧。

编写广播(Python)(C++)。

本教程教如何向tf2广播机器人的状态。

编写监听器(Python)(C++)。

本教程教如何使用tf2访问帧变换。

添加框架(Python)(C++)。

本教程教如何向tf2添加额外的固定帧。

使用时间(Python)(C++)。

本教程教使用lookup_transform函数中的超时来等待tf2树上的转换可用。

时间旅行(Python)(C++)。

本教程向介绍tf2的高级时间旅行功能。

调试tf2

四元数基本原理。

本教程介绍ROS 2中四元数的基本用法。

调试tf2问题。

本教程向介绍调试tf2相关问题的系统方法。

将传感器消息与tf2一起使用

对tf2_ros::MessageFilter使用标记数据类型。

本教程教您如何使用tf2_ros::MessageFilter处理标记的数据类型。

相关文章:

ROS2机器人编程简述humble-第四章-BASIC DETECTOR .3

书中程序适用于turtlebot、husky等多种机器人&#xff0c;配置相似都可以用的。支持ROS2版本foxy、humble。基础检测效果如下&#xff1a;由于缺&#xffe5;&#xff0c;所有设备都非常老旧&#xff0c;都是其他实验室淘汰或者拼凑出来的设备。机器人控制笔记本是2010年版本。…...

【图像分类】基于PyTorch搭建LSTM实现MNIST手写数字体识别(双向LSTM,附完整代码和数据集)

写在前面&#xff1a; 首先感谢兄弟们的关注和订阅&#xff0c;让我有创作的动力&#xff0c;在创作过程我会尽最大能力&#xff0c;保证作品的质量&#xff0c;如果有问题&#xff0c;可以私信我&#xff0c;让我们携手共进&#xff0c;共创辉煌。 在https://blog.csdn.net/A…...

【Linux】多线程编程 - 同步/条件变量/信号量

目录 一.线程同步 1.什么是线程同步 2.为什么需要线程同步 3.如何实现线程同步 二.条件变量 1.常见接口以及使用 2.wiat/signal中的第二个参数mutex的意义 3.代码验证 三.POSIX信号量 1.概念 2.常见接口以及使用 四.条件变量vsPOSIX信号量 一.线程同步 1.什么是线…...

ES优化方案

ES优化&联合HBASE&#xff1a; 【Elasticsearch】优秀实践-ESHbase的实现_少加点香菜的博客-CSDN博客_sceshbase ES写入性能优化方案 ElasticSearch 调优笔记_index.refresh_interval_六月飞雪的博客-CSDN博客 es如何提升写入性能_婲落ヽ紅顏誶的博客-CSDN博客_es写入性…...

从数据备份保护到完整生命周期管理平台,爱数全新发布 AnyBackup Family 8

编辑 | 宋慧 出品 | CSDN 云计算 从2003年创业&#xff0c;开始做数据备份技术&#xff0c;爱数已经走过了近20年的时间。现在&#xff0c;数据的价值被越来越多的业界与用户看到&#xff0c;数据分析应用赛道近年一直持续火热。而现在的爱数在做的&#xff0c;已经从数据的备…...

Go 微服务开发框架 DMicro 的设计思路

Go 微服务开发框架 DMicro 的设计思路 DMicro 源码地址: Gitee:dmicro: dmicro是一个高效、可扩展且简单易用的微服务框架。包含drpc,dserver等 背景 DMicro 诞生的背景&#xff0c;是因为我写了 10 来年的 PHP&#xff0c;想在公司内部推广 Go, 公司内部的组件及 rpc 协议都…...

浅谈功能测试

1.功能测试流程 1.1 功能测试流程 # 功能测试大致按照以下流程进行: (1).需求分析与评审(2).测试计划与测试方案(3).测试用例设计(4).测试用例评审(5).执行用例(6).缺陷跟踪及报告产出 1.2 功能测试流程详解 (1).需求分析与评审 功能测试应从需求出发, 功能测试就是尽量覆…...

UDP的详细解析

UDP的详细解析 文章目录UDP的详细解析UDP 概述UDP的首部格式检验和的计算抓包测试参考TCP/IP运输层的两个主要协议都是互联网的正式标准&#xff0c;即&#xff1a;用户数据报协议UDP (User Datagram Protocol)传输控制协议TCP (Transmission Control Protocol) 按照OSI的术语…...

史上最详细JUC教程之Synchronized与锁升级详解

在Java早期版本中&#xff0c;synchronized属于重量级锁&#xff0c;效率低下&#xff0c;因为监视器锁&#xff08;monitor&#xff09;是依赖于底层的操作系统的Mutex Lock来实现的&#xff0c;挂起线程和恢复线程都需要转入内核态去完成&#xff0c;阻塞或唤醒一个Java线程需…...

Vue|初识Vue

Vue是一款用于构建用户界面的JavaScript框架。它基于标准HTML、CSS和JavaScript构建&#xff0c;并提供了一套声明式的、组件化的编程模型&#xff0c;帮助开发者高效地开发用户界面。 初识Vue1. Vue简介2. 开发准备3. 模板语法3.1 差值语法3.2 指令语法4. 数据绑定4.1 单向数据…...

在职阿里6年,一个29岁女软件测试工程师的心声

简单的先说一下&#xff0c;坐标杭州&#xff0c;14届本科毕业&#xff0c;算上年前在阿里巴巴的面试&#xff0c;一共有面试了有6家公司&#xff08;因为不想请假&#xff0c;因此只是每个晚上去其他公司面试&#xff0c;所以面试的公司比较少&#xff09;其中成功的有4家&…...

(C语言)自定义类型,枚举与联合

问&#xff1a;1. 结构体在自引用的时候不能怎么样&#xff1f;可以怎么样&#xff1f;2. Solve the problems&#xff1a;自定义一个学生结构体类型&#xff0c;要包含姓名&#xff0c;性别&#xff0c;年龄&#xff0c;六科成绩&#xff0c;家乡&#xff08;也为结构体&#…...

node.js服务端笔记文档学会写接口,学习分类:path、包、模块化、fs、express、中间件、jwt、开发模式、cors。

node.js 学习笔记 node.js服务端笔记文档学会写接口&#xff0c;path、包、模块化、fs、express、中间件、JWT、开发模式、cors。 gitee&#xff1a;代码接口笔记 1什么是node.js nodejs 是基于ChromeV8&#xff0c;引擎的一个javaScript 运行环境。node.js 无法使用DOM和BO…...

初始C++(三):引用

文章目录一.引用的概念二.引用的使用1.引用作为输出型参数2. 引用作为函数返回值3.const引用三.引用的一些小问题四.引用和指针五.引用和指针的区别一.引用的概念 引用的作用是给一个已经存在的变量取别名&#xff0c;编译器不会为引用变量开空间&#xff0c;引用变量和被他引…...

【前端】参考C站动态发红包界面,高度还原布局和交互

最近有些小伙伴咨询博主说前端布局好难&#xff0c;其实都是熟能生巧&#xff01; 模仿C站动态发红包界面&#xff0c;cssdiv实现布局&#xff0c;纯javascript实现交互效果 目录 1、界面效果 2、界面分析 2.1、整体结构 2.2、标题 2.3、表单 2.4、按钮 3、代码实现 3.…...

VR全景带你浪漫“狂飙”情人节,见证甜蜜心动

当情人节遇上VR&#xff0c;足以让情侣过一个难忘的情人节。马上情人节就要到了&#xff0c;大家是不是还在绞尽脑汁的想着&#xff0c;如何和另一半过一个浪漫的情人节呢&#xff1f;老套的剧情已经不能吸引人了&#xff0c;让我们看看VR全景给情人节带来了哪些不同的体验吧&a…...

Linux系统安全之iptables防火墙

目录 一.iptables防火墙基本介绍 二.iptables的四表五链 三.iptables的配置 1.iptables的安装 2.iptables防火墙的配置方法 四.添加、查看、删除规则 1.查看(fliter)表中的所有链 iptables -L 2.使用数字形式(fliter)表所有链 查看输出结果 iptables -nL 3.清空表中所…...

【C#基础】C# 变量与常量的使用

序号系列文章1【C#基础】C# 程序通用结构2【C#基础】C# 基础语法解析3【C#基础】C# 数据类型总结文章目录前言一. 变量&#xff08;variable&#xff09;1&#xff0c;变量定义及初始化2&#xff0c;变量的类别3&#xff0c;接收输出变量二. 常量&#xff08;constant&#xff…...

[ 常用工具篇 ] CobaltStrike(CS神器)基础(一) -- 安装及设置监听器详解

&#x1f36c; 博主介绍 &#x1f468;‍&#x1f393; 博主介绍&#xff1a;大家好&#xff0c;我是 _PowerShell &#xff0c;很高兴认识大家~ ✨主攻领域&#xff1a;【渗透领域】【数据通信】 【通讯安全】 【web安全】【面试分析】 &#x1f389;点赞➕评论➕收藏 养成习…...

Redis集群

Redis集群 本章是基于CentOS7下的Redis集群教程&#xff0c;包括&#xff1a; 单机安装RedisRedis主从Redis分片集群 1.单机安装Redis 首先需要安装Redis所需要的依赖&#xff1a; yum install -y gcc tcl然后将课前资料提供的Redis安装包上传到虚拟机的任意目录&#xff…...

利用ngx_stream_return_module构建简易 TCP/UDP 响应网关

一、模块概述 ngx_stream_return_module 提供了一个极简的指令&#xff1a; return <value>;在收到客户端连接后&#xff0c;立即将 <value> 写回并关闭连接。<value> 支持内嵌文本和内置变量&#xff08;如 $time_iso8601、$remote_addr 等&#xff09;&a…...

循环冗余码校验CRC码 算法步骤+详细实例计算

通信过程&#xff1a;&#xff08;白话解释&#xff09; 我们将原始待发送的消息称为 M M M&#xff0c;依据发送接收消息双方约定的生成多项式 G ( x ) G(x) G(x)&#xff08;意思就是 G &#xff08; x ) G&#xff08;x) G&#xff08;x) 是已知的&#xff09;&#xff0…...

ssc377d修改flash分区大小

1、flash的分区默认分配16M、 / # df -h Filesystem Size Used Available Use% Mounted on /dev/root 1.9M 1.9M 0 100% / /dev/mtdblock4 3.0M...

UDP(Echoserver)

网络命令 Ping 命令 检测网络是否连通 使用方法: ping -c 次数 网址ping -c 3 www.baidu.comnetstat 命令 netstat 是一个用来查看网络状态的重要工具. 语法&#xff1a;netstat [选项] 功能&#xff1a;查看网络状态 常用选项&#xff1a; n 拒绝显示别名&#…...

基础测试工具使用经验

背景 vtune&#xff0c;perf, nsight system等基础测试工具&#xff0c;都是用过的&#xff0c;但是没有记录&#xff0c;都逐渐忘了。所以写这篇博客总结记录一下&#xff0c;只要以后发现新的用法&#xff0c;就记得来编辑补充一下 perf 比较基础的用法&#xff1a; 先改这…...

《基于Apache Flink的流处理》笔记

思维导图 1-3 章 4-7章 8-11 章 参考资料 源码&#xff1a; https://github.com/streaming-with-flink 博客 https://flink.apache.org/bloghttps://www.ververica.com/blog 聚会及会议 https://flink-forward.orghttps://www.meetup.com/topics/apache-flink https://n…...

【OSG学习笔记】Day 16: 骨骼动画与蒙皮(osgAnimation)

骨骼动画基础 骨骼动画是 3D 计算机图形中常用的技术&#xff0c;它通过以下两个主要组件实现角色动画。 骨骼系统 (Skeleton)&#xff1a;由层级结构的骨头组成&#xff0c;类似于人体骨骼蒙皮 (Mesh Skinning)&#xff1a;将模型网格顶点绑定到骨骼上&#xff0c;使骨骼移动…...

力扣-35.搜索插入位置

题目描述 给定一个排序数组和一个目标值&#xff0c;在数组中找到目标值&#xff0c;并返回其索引。如果目标值不存在于数组中&#xff0c;返回它将会被按顺序插入的位置。 请必须使用时间复杂度为 O(log n) 的算法。 class Solution {public int searchInsert(int[] nums, …...

AI,如何重构理解、匹配与决策?

AI 时代&#xff0c;我们如何理解消费&#xff1f; 作者&#xff5c;王彬 封面&#xff5c;Unplash 人们通过信息理解世界。 曾几何时&#xff0c;PC 与移动互联网重塑了人们的购物路径&#xff1a;信息变得唾手可得&#xff0c;商品决策变得高度依赖内容。 但 AI 时代的来…...

A2A JS SDK 完整教程:快速入门指南

目录 什么是 A2A JS SDK?A2A JS 安装与设置A2A JS 核心概念创建你的第一个 A2A JS 代理A2A JS 服务端开发A2A JS 客户端使用A2A JS 高级特性A2A JS 最佳实践A2A JS 故障排除 什么是 A2A JS SDK? A2A JS SDK 是一个专为 JavaScript/TypeScript 开发者设计的强大库&#xff…...