Robot Operating System——Service的同步/异步通信

news2024/12/27 13:28:18

大纲

  • Service模式的服务端
    • 请求响应函数
    • 启动Service
    • 停止Service
    • 完整代码
  • Service模式的客户端
    • 异步模式的客户端
      • 完整代码
    • 同步模式的客户端
      • 完整代码
  • 测试
    • 长期运行的服务
    • 发送请求
    • 响应一次的服务
      • 发送请求
  • 参考资料

在ROS 2中,除了 《Robot Operating System——topic的发布和订阅》介绍的Topic,还有其他通信机制。Service就是其中一种。

Service是一种同步的请求/响应通信机制。一个节点可以提供一个Service,其他节点可以请求这个Service,并等待响应。Service由Service类型定义,包括请求和响应消息。

Service模式的服务端

我们参考demo_nodes_cpp/src/services/add_two_ints_server.cpp的例子来讲Service的实现。

class ServerNode final : public rclcpp::Node
{
public:
  DEMO_NODES_CPP_PUBLIC
  explicit ServerNode(const rclcpp::NodeOptions & options)
  : Node("add_two_ints_server", options)
  {
……
  }
  
private:
  rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr srv_;
  rclcpp::TimerBase::SharedPtr timer_;
  bool saw_request_{false};
};

ServerNode继承于rclcpp::Node,它包含了一个rclcpp::Service模板类的智能指针成员变量srv_。模板参数是一个通过IDL文件生成的结构体example_interfaces::srv::AddTwoInts。这个IDL文件可以参考https://github.com/ros2/example_interfaces/blob/rolling/srv/AddTwoInts.srv。其内容也很简单:int64类型的a和b是这个Service的Request部分,int64类型的sum是这个Service的Response部分。

int64 a
int64 b
---
int64 sum

上述srv文件会通过rosidl_generator_cpp编译成C++版本对应的代码文件。这个文件会比较长,其部分内容如下

template<class ContainerAllocator>
struct AddTwoInts_Request_
{
  using Type = AddTwoInts_Request_<ContainerAllocator>;

  explicit AddTwoInts_Request_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL)
  {
    if (rosidl_runtime_cpp::MessageInitialization::ALL == _init ||
      rosidl_runtime_cpp::MessageInitialization::ZERO == _init)
    {
      this->a = 0ll;
      this->b = 0ll;
    }
  }

  explicit AddTwoInts_Request_(const ContainerAllocator & _alloc, rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL)
  {
    (void)_alloc;
    if (rosidl_runtime_cpp::MessageInitialization::ALL == _init ||
      rosidl_runtime_cpp::MessageInitialization::ZERO == _init)
    {
      this->a = 0ll;
      this->b = 0ll;
    }
  }

  // field types and members
  using _a_type =
    int64_t;
  _a_type a;
  using _b_type =
    int64_t;
  _b_type b;

……
template<class ContainerAllocator>
struct AddTwoInts_Response_
{
  using Type = AddTwoInts_Response_<ContainerAllocator>;

  explicit AddTwoInts_Response_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL)
  {
    if (rosidl_runtime_cpp::MessageInitialization::ALL == _init ||
      rosidl_runtime_cpp::MessageInitialization::ZERO == _init)
    {
      this->sum = 0ll;
    }
  }

  explicit AddTwoInts_Response_(const ContainerAllocator & _alloc, rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL)
  {
    (void)_alloc;
    if (rosidl_runtime_cpp::MessageInitialization::ALL == _init ||
      rosidl_runtime_cpp::MessageInitialization::ZERO == _init)
    {
      this->sum = 0ll;
    }
  }

  // field types and members
  using _sum_type =
    int64_t;
  _sum_type sum;

……

struct AddTwoInts
{
  using Request = example_interfaces::srv::AddTwoInts_Request;
  using Response = example_interfaces::srv::AddTwoInts_Response;
  using Event = example_interfaces::srv::AddTwoInts_Event;
};

请求响应函数

回到Demo中。下一步我们需要设置Service收到请求时的响应函数。

    auto handle_add_two_ints = [this](
      const std::shared_ptr<rmw_request_id_t> request_header,
      const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
      std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) -> void
      {
        (void)request_header;
        RCLCPP_INFO(
          this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64,
          request->a, request->b);
        response->sum = request->a + request->b;

        saw_request_ = true;
      };

这个函数接受三个参数:

  • 请求头。它是rmw_request_id_t类型,和我们之前定义的srv文件无关。
/// An rmw service request identifier
typedef struct RMW_PUBLIC_TYPE rmw_request_id_s
{
  /// The guid of the writer associated with this request
  uint8_t writer_guid[RMW_GID_STORAGE_SIZE];

  /// Sequence number of this service
  int64_t sequence_number;
} rmw_request_id_t;
  • 请求体。它是srv文件上半部分的内容生成的结构体example_interfaces::srv::AddTwoInts::Request。
  • 返回体。他是srv文件下半部分的内容生成的结构体example_interfaces::srv::AddTwoInts::response。

请求体和返回体中的成员变量都是public类型,可以很方便的直接访问。

如函数名handle_add_two_ints 所表达的,这个lambda函数就是将请求中的参数a和b相加,设置到返回体的sum中。

启动Service

我们可以通过Node基类的create_service方法创建并启动Service。传递的第一个参数是Service的名称,第二个参数是其请求处理函数,即上面见到的lambda函数。

    // Create a service that will use the callback function to handle requests.
    srv_ = create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", handle_add_two_ints);

停止Service

下面这段代码,会根据程序启动时所携带的参数one_shot决定这个服务是一个长期运行的服务,还是响应了一些请求后自动退出的服务。

如果one_shot 为true,则会启动一个每隔100毫秒轮询一次的定时器,检查是否已经响应过请求。如果相应过了,则调用rclcpp::shutdown()来停止Node,进而停止服务;如果没有响应过,则继续轮询。

    bool one_shot = this->declare_parameter("one_shot", false);
    if (one_shot) {
      timer_ = this->create_wall_timer(
        std::chrono::milliseconds(100),
        [this]() {
          if (saw_request_) {
            rclcpp::shutdown();
          }
        });
    }

完整代码

// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// 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 <chrono>
#include <cinttypes>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"

#include "example_interfaces/srv/add_two_ints.hpp"

#include "demo_nodes_cpp/visibility_control.h"

namespace demo_nodes_cpp
{

class ServerNode final : public rclcpp::Node
{
public:
  DEMO_NODES_CPP_PUBLIC
  explicit ServerNode(const rclcpp::NodeOptions & options)
  : Node("add_two_ints_server", options)
  {
    auto handle_add_two_ints = [this](
      const std::shared_ptr<rmw_request_id_t> request_header,
      const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
      std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) -> void
      {
        (void)request_header;
        RCLCPP_INFO(
          this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64,
          request->a, request->b);
        response->sum = request->a + request->b;

        saw_request_ = true;
      };
    // Create a service that will use the callback function to handle requests.
    srv_ = create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", handle_add_two_ints);

    bool one_shot = this->declare_parameter("one_shot", false);
    if (one_shot) {
      timer_ = this->create_wall_timer(
        std::chrono::milliseconds(100),
        [this]() {
          if (saw_request_) {
            rclcpp::shutdown();
          }
        });
    }
  }

private:
  rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr srv_;
  rclcpp::TimerBase::SharedPtr timer_;
  bool saw_request_{false};
};

}  // namespace demo_nodes_cpp

RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::ServerNode)

Service模式的客户端

ROS2的Client基类只提供了异步请求客户端的方案。但是对于异步结果,我们可以选择等待返回,从而实现同步请求的功能。我们先看下异步模式。

异步模式的客户端

我们参考demo_nodes_cpp/src/services/add_two_ints_client_async.cpp的实现。

class ClientNode : public rclcpp::Node
{
public:
  DEMO_NODES_CPP_PUBLIC
  explicit ClientNode(const rclcpp::NodeOptions & options)
  : Node("add_two_ints_client", options)
  {
    setvbuf(stdout, NULL, _IONBF, BUFSIZ);
    client_ = create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");
    queue_async_request();
  }
……

private:
  rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
};

我们需要使用之前srv文件生成的example_interfaces::srv::AddTwoInts作为模板参数,构建一个rclcpp::Client模板类。然后通过queue_async_request()来发送请求。

  DEMO_NODES_CPP_PUBLIC
  void queue_async_request()
  {
    while (!client_->wait_for_service(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
        return;
      }
      RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
    }
    auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
    request->a = 2;
    request->b = 3;

    // We give the async_send_request() method a callback that will get executed once the response
    // is received.
    // This way we can return immediately from this method and allow other work to be done by the
    // executor in `spin` while waiting for the response.
    using ServiceResponseFuture =
      rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedFuture;
    auto response_received_callback = [this](ServiceResponseFuture future) {
        auto result = future.get();
        RCLCPP_INFO(this->get_logger(), "Result of add_two_ints: %" PRId64, result->sum);
        rclcpp::shutdown();
      };
    auto future_result = client_->async_send_request(request, response_received_callback);
  }

我们先要通过client_->wait_for_service(1s)来检测服务端是否处于Ready状态。

如果是Ready状态,则构建Request结构体并设置参数。

然后创建一个用于接收异步请求返回结果的回调函数,它的参数是rclcpp::Client模板类的SharedFuture。

最后通过async_send_request发送请求。

需要注意的是,由于我们使用的是Node来发送请求,所以在async_send_request调用结束后,程序还在运行,只是处于idle状态。当服务端返回时,response_received_callback 回调函数会被执行,我们可以通过其入参拿到结果,然后调用rclcpp::shutdown()来终止这个Node的运行。

完整代码

// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// 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 <chrono>
#include <cinttypes>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"

#include "example_interfaces/srv/add_two_ints.hpp"

#include "demo_nodes_cpp/visibility_control.h"

using namespace std::chrono_literals;

namespace demo_nodes_cpp
{
class ClientNode : public rclcpp::Node
{
public:
  DEMO_NODES_CPP_PUBLIC
  explicit ClientNode(const rclcpp::NodeOptions & options)
  : Node("add_two_ints_client", options)
  {
    setvbuf(stdout, NULL, _IONBF, BUFSIZ);
    client_ = create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");
    queue_async_request();
  }

  DEMO_NODES_CPP_PUBLIC
  void queue_async_request()
  {
    while (!client_->wait_for_service(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
        return;
      }
      RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
    }
    auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
    request->a = 2;
    request->b = 3;

    // We give the async_send_request() method a callback that will get executed once the response
    // is received.
    // This way we can return immediately from this method and allow other work to be done by the
    // executor in `spin` while waiting for the response.
    using ServiceResponseFuture =
      rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedFuture;
    auto response_received_callback = [this](ServiceResponseFuture future) {
        auto result = future.get();
        RCLCPP_INFO(this->get_logger(), "Result of add_two_ints: %" PRId64, result->sum);
        rclcpp::shutdown();
      };
    auto future_result = client_->async_send_request(request, response_received_callback);
  }

private:
  rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
};

}  // namespace demo_nodes_cpp

RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::ClientNode)

同步模式的客户端

同步发送的模式,就是等待异步执行完毕。我们只要等待上述SharedFuture即可。

这次我们参考demo_nodes_cpp/src/services/add_two_ints_client.cpp。它不再使用Node模式,而是直接编译成一个可执行文件。

int main(int argc, char ** argv)
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);

  rclcpp::init(argc, argv);

  auto node = rclcpp::Node::make_shared("add_two_ints_client");

  auto client = node->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");

  auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
  request->a = 2;
  request->b = 3;

  while (!client->wait_for_service(1s)) {
    if (!rclcpp::ok()) {
      RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
      return 0;
    }
    RCLCPP_INFO(node->get_logger(), "service not available, waiting again...");
  }

  // TODO(wjwwood): make it like `client->send_request(node, request)->sum`
  // TODO(wjwwood): consider error condition
  auto result = send_request(node, client, request);
  if (result) {
    RCLCPP_INFO_STREAM(node->get_logger(), "Result of add_two_ints: " << result->sum);
  } else {
    RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for response. Exiting.");
  }

  rclcpp::shutdown();
  return 0;
}

其过程也和异步模式很像,我们主要关注下实现了同步等待功能的send_request是怎么实现的。

// TODO(wjwwood): make this into a method of rclcpp::Client.
example_interfaces::srv::AddTwoInts::Response::SharedPtr send_request(
  rclcpp::Node::SharedPtr node,
  rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client,
  example_interfaces::srv::AddTwoInts::Request::SharedPtr request)
{
  auto result = client->async_send_request(request);
  // Wait for the result.
  if (rclcpp::spin_until_future_complete(node, result) ==
    rclcpp::FutureReturnCode::SUCCESS)
  {
    return result.get();
  } else {
    return NULL;
  }
}

可以看到,这次对于异步请求,我们没有再设置回调函数,而是直接通过rclcpp::spin_until_future_complete来等待SharedFuture即可;如果等到了就返回对应的值。

完整代码

// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// 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 <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"

#include "example_interfaces/srv/add_two_ints.hpp"

using namespace std::chrono_literals;

// TODO(wjwwood): make this into a method of rclcpp::Client.
example_interfaces::srv::AddTwoInts::Response::SharedPtr send_request(
  rclcpp::Node::SharedPtr node,
  rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client,
  example_interfaces::srv::AddTwoInts::Request::SharedPtr request)
{
  auto result = client->async_send_request(request);
  // Wait for the result.
  if (rclcpp::spin_until_future_complete(node, result) ==
    rclcpp::FutureReturnCode::SUCCESS)
  {
    return result.get();
  } else {
    return NULL;
  }
}

int main(int argc, char ** argv)
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);

  rclcpp::init(argc, argv);

  auto node = rclcpp::Node::make_shared("add_two_ints_client");

  auto client = node->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");

  auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
  request->a = 2;
  request->b = 3;

  while (!client->wait_for_service(1s)) {
    if (!rclcpp::ok()) {
      RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
      return 0;
    }
    RCLCPP_INFO(node->get_logger(), "service not available, waiting again...");
  }

  // TODO(wjwwood): make it like `client->send_request(node, request)->sum`
  // TODO(wjwwood): consider error condition
  auto result = send_request(node, client, request);
  if (result) {
    RCLCPP_INFO_STREAM(node->get_logger(), "Result of add_two_ints: " << result->sum);
  } else {
    RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for response. Exiting.");
  }

  rclcpp::shutdown();
  return 0;
}

测试

长期运行的服务

./build/demo_nodes_cpp/add_two_ints_server 

发送请求

./build/demo_nodes_cpp/add_two_ints_client_async

在这里插入图片描述
服务端相应
在这里插入图片描述
同步模式类似,不再演示。

响应一次的服务

我们将one_shot设置为true,让其响应一次后,通过rclcpp::shutdown()来关闭Node,进而关闭服务。

./build/demo_nodes_cpp/add_two_ints_server --ros-args -p one_shot:=true

发送请求

./build/demo_nodes_cpp/add_two_ints_client

在这里插入图片描述
服务端相应
在这里插入图片描述
可以看到服务端响应后就退出了。

参考资料

  • https://github.com/ros2/example_interfaces/blob/rolling/srv/AddTwoInts.srv

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

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

相关文章

汇昌联信科技拼多多怎么样?

汇昌联信科技拼多多怎么样?汇昌联信科技是一家专注于提供电子商务解决方案的公司&#xff0c;其业务涉及多个电商平台&#xff0c;其中就包括了国内知名的电商平台——拼多多。对于汇昌联信科技在拼多多上的表现&#xff0c;我们可以从以下几个方面来进行深入的探讨和分析。 一…

智慧校园灵动资源调配系统【SpringBoot+Vue】(Java课设)

客官进来看一眼呗&#xff0c;有惊喜&#xff01;【帮你解决烦恼】&#xff1a;Java课设和计Java毕设太难不会做怎么办&#xff1f; 系统类型 【SpringBootVue】类型的系统 使用范围 适合作为Java课设&#xff01;&#xff01;&#xff01; 部署环境 jdk1.8Idea 运行效果…

2024.7.22 作业

1.将双向链表和循环链表自己实现一遍&#xff0c;至少要实现创建、增、删、改、查、销毁工作 循环链表 looplinklist.h #ifndef LOOPLINKLIST_H #define LOOPLINKLIST_H#include <myhead.h>typedef int datatype;typedef struct Node {union {int len;datatype data;}…

Jetpack Compose 通过 OkHttp 发送 HTTP 请求的示例

下面是一个使用 Kotlin 和 Jetpack Compose 来演示通过 OkHttp 发送 HTTP 请求的示例。这个示例包括在 Jetpack Compose 中发送一个 GET 请求和一个 POST 请求&#xff0c;并显示结果。 添加okhttp依赖 首先&#xff0c;在你的 build.gradle.kts 文件中添加必要的依赖&#xf…

解决:uniapp 小程序 使用swiper 内部嵌套另外一个拥有左右滑动组件导致滑动冲突

解决办法 在swiper-item 内增加这个属性进行包裹 touchmove.stop <div touchmove.stop><qiun-data-charts type"area" :opts"optsStg" :chartData"dateDataStg" /> </div>

最优化理论与方法-第十讲-对偶理论的基本性质和割平面法

文章目录 1. 向量化拉格朗日对偶函数2. 对偶问题是凹函数3. 对偶问题转换4. 外逼近法4.1 步骤4.2 注意事项 1. 向量化拉格朗日对偶函数 ( D ) max ⁡ d ( λ , μ ) s t . λ i ≥ 0 , i 1 , ⋯ , m , d ( λ , μ ) min ⁡ x ∈ X { f ( x ) ∑ i 1 m λ i g i ( x ) ∑ …

传神社区|数据集合集第7期|法律NLP数据集合集

自从ChatGPT等大型语言模型&#xff08;Large Language Model, LLM&#xff09;出现以来&#xff0c;其类通用人工智能&#xff08;AGI&#xff09;能力引发了自然语言处理&#xff08;NLP&#xff09;领域的新一轮研究和应用浪潮。尤其是ChatGLM、LLaMA等普通开发者都能运行的…

CrowdStrike更新致850万Windows设备宕机,微软紧急救火!

7月18日&#xff0c;网络安全公司CrowdStrike发布了一次软件更新&#xff0c;导致全球大范围Windows系统宕机。 预估CrowdStrike的更新影响了将近850万台Windows设备&#xff0c;多行业服务因此停滞&#xff0c;全球打工人原地放假&#xff0c;坐等吃瓜&#xff0c;网络上爆梗…

TCP并发服务器多线程

1.创建线程‐‐pthread_create int pthread_create( pthread_t *thread, // 线程 ID 无符号长整型 const pthread_attr_t *attr, // 线程属性&#xff0c; NULL void *(*start_routine)(void *), // 线程处理函数 void *arg); // 线程处理函数 参数&#xff1a; pthrea…

EXCEL怎么自动添加表格吗?

第一步&#xff0c;选中需要添加表格的范围 第二步&#xff0c;点击开始&#xff0c;选择条件格式&#xff0c;“使用公式确定要设置格式的单元格” 第三步&#xff0c;编辑规则说明加上<>"" 第四步&#xff0c;点击边框&#xff0c;选择外边框确定即可&#x…

STM32CubeIDE(CAN)

目录 一、概念 1、简述 2、CAN 的几种模式 二、实践 1、环回模式轮询通信 1.1 软件配置 1.2 代码编写 2、环回模式中断通信 2.1 软件配置 2.2 代码编写 一、概念 1、简述 STM32微控制器系列包含多个型号&#xff0c;其中一些型号集成了CAN&#xff08;Controller Are…

用移动硬盘装系统里面资料会全删吗?误装系统怎么办

使用‌移动硬盘装系统是一种可行的选择&#xff0c;尤其是当你需要在多台电脑上使用相同的操作系统时。然而&#xff0c;对于初次尝试的新手来说&#xff0c;可能会有一些疑虑&#xff1a;在将移动硬盘用作系统安装盘后&#xff0c;原有的数据是否会被完全删除&#xff1f;如果…

邮件安全篇:邮件反垃圾系统运作机制简介

1. 什么是邮件反垃圾系统&#xff1f; 邮件反垃圾系统是一种专门设计用于检测、过滤和阻止垃圾邮件的技术解决方案。用于保护用户的邮箱免受未经请求的商业广告、诈骗信息、恶意软件、钓鱼攻击和其他非用户意愿接收的电子邮件的侵扰。 反垃圾系统的常见部署形式 2. 邮件反垃圾…

3GPP眼中的XR及其技术特点

3GPP R18 支持了XR Services。XR需要高数据速率和低延迟通信&#xff0c;这也真是5G可以大展身手的地方。这篇就从3GPP的角度看下XR是什么以及XR有哪些技术特点。 Extended Reality (XR) 是指由计算机技术和可穿戴设备生成的所有现实与虚拟相结合的环境和人机交互技术。 实际上…

【ELK】window下ELK的安装与部署

ELK的安装与部署 1. 下载2. 配置&启动2.1 elasticsarch2.1.1 生成证书2.1.2 生成秘钥2.1.3 将凭证迁移到指定目录2.1.4 改配置2.1.5 启动2.1.6 访问测试2.1.7 生成kibana账号 2.2 kibana2.2.1 改配置2.2.2 启动2.2.3 访问测试 2.3 logstash2.3.1 改配置2.3.2 启动 2.4 file…

SQL injection UNION attacks SQL注入联合查询攻击

通过使用UNION关键字&#xff0c;拼接新的SQL语句从而获得额外的内容&#xff0c;例如 select a,b FROM table1 UNION select c,d FROM table2&#xff0c;可以一次性查询 2行数据&#xff0c;一行是a&#xff0c;b&#xff0c;一行是c&#xff0c;d。 UNION查询必须满足2个条…

Potree在web端显示大型点云模型文件

一、克隆项目代码&#xff08;准备好上网工具&#xff0c;得先有node.js npm 环境&#xff09; git clone https://github.com/potree/potree.git二、依赖安装&#xff08;换淘宝镜像能快一些&#xff09; cd potree npm install三、运行 npm start四、使用样例 打开浏览器…

【Linux学习】常用基本指令

&#x1f525;个人主页&#xff1a; Forcible Bug Maker &#x1f525;专栏&#xff1a;Linux学习 目录 &#x1f308;前言&#x1f525;XShell的一些使用查看Linux主机IP使用XShell登录主机XShell下的复制粘贴 &#x1f525;Linux下常用基本指令ls指令pwd指令cd指定touch指令…

Java:115-Spring Boot的底层原理(下篇)

这里续写上一章博客&#xff08;115章博客&#xff09; SpringBoot视图技术&#xff1a; 支持的视图技术 &#xff1a; 前端模板引擎技术的出现&#xff08;jsp也是&#xff09;&#xff0c;使前端开发人员无需关注后端业务的具体实现&#xff08;jsp中&#xff0c;具体的…

Windows 如何把软件从C盘移到其他盘

不知道您有没有发现&#xff0c;当我们下载安装程序时&#xff0c;程序通常会默认自动安装在C盘驱动器中&#xff0c;如果您不手动修改路径的话&#xff0c;C盘驱动器上的可用空间将逐渐减少&#xff0c;并会在不久的将来出现 C盘已满 问题&#xff0c;这可能会导致您的电脑性能…