moveit2基础教程上手-使用xarm6演示
0、前置信息
开发环境:wsl
。
ros版本:jazzy
,ubuntu版本:24.04
xarm-ros2地址
1、启动Rviz,加载 Motion Planning Plugin,实现演示功能
Getting Started — MoveIt Documentation: Rolling documentation
ros2 launch xarm_moveit_config xarm6_moveit_fake.launch.py add_gripper:=True
2、first C++ moveit project
Your First C++ MoveIt Project — MoveIt Documentation: Rolling documentation
ros2 pkg create \--build-type ament_cmake \--dependencies moveit_ros_planning_interface rclcpp \--node-name hello_moveit hello_moveit
编写src/hello_moveit.cpp
#include <memory>#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.hpp>int main(int argc, char ** argv)
{// Initialize ROSrclcpp::init(argc, argv);auto const node = std::make_shared<rclcpp::Node>("hello_moveit",rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));// Create ROS loggerauto const logger = rclcpp::get_logger("hello_moveit");// log infoRCLCPP_INFO(logger, "Hello MoveIt2!");// Shutdown ROSrclcpp::shutdown();return 0;
}
编译运行!
# build
colcon build --packages-select hello_moveit
# source env
source install/setup.bash
# Run node
ros2 run hello_moveit hello_moveit
3、增加功能,使用movegroupinterface进行规划和执行
// Create the MoveIt MoveGroup Interface
using moveit::planning_interface::MoveGroupInterface;
// node, group_name 注意这里替换为xarm6
auto move_group_interface = MoveGroupInterface(node, "xarm6");// Set a target pose
auto const target_pose = []{geometry_msgs::msg::Pose msg;msg.position.x = 0.3;msg.position.y = -0.1;msg.position.z = 0.2;msg.orientation.x = 1;msg.orientation.y = 0;msg.orientation.z = 0;msg.orientation.w = 0;return msg;}();
move_group_interface.setPoseTarget(target_pose);// Create a plan to that target pose
auto const [success, plan] = [&move_group_interface]{
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
auto const ok = static_cast<bool>(move_group_interface.plan(my_plan));
return std::make_pair(ok, my_plan);
}();// Execute the plan
if(success) {
move_group_interface.execute(plan);
} else {
RCLCPP_ERROR(logger, "Planning failed!");
}
(补充)使用lambda进行复杂初始化:IIFE for Complex Initialization - C++ Stories
// lambda 范式,[& / =] 按引用 / 值捕获所有使用的外部变量
[capture list] (parameter list) -> return type { function body }// ex.
const auto var = [&] { return /* some complex code here */;
}(); // call it!
然后在 Displays
窗口的 MotionPlanning/Planning Request
下,取消选中 Query Goal State
框。
编译运行(报错记录,已解决)(只运行节点似乎缺少关键配置项robot_description_semantic
,对比xarm_planner中的launch文件发现)
ros2 run hello_moveit hello_moveit
在类中使用参数(C++) — ROS 2 Documentation: Humble 文档
dod@qDoDp:~/dev_ws$ ros2 run hello_moveit hello_moveit
[INFO] [1742572281.073652608] [hello_moveit]: Hello MoveIt2!
[ERROR] [1742572291.184066819] [hello_moveit]: Could not find parameter robot_description_semantic and did not receive robot_description_semantic via std_msgs::msg::String subscription within 10.000000 seconds.
Error: Could not parse the SRDF XML File. Error=XML_ERROR_EMPTY_DOCUMENT ErrorID=13 (0xd) Line number=0at line 732 in ./src/model.cpp
[ERROR] [1742572291.194733210] [moveit_2235338666.moveit.ros.rdf_loader]: Unable to parse SRDF
[FATAL] [1742572291.195511210] [moveit_2235338666.moveit.ros.move_group_interface]: Unable to construct robot model. Please make sure all needed information is on the parameter server.
terminate called after throwing an instance of 'std::runtime_error'what(): Unable to construct robot model. Please make sure all needed information is on the parameter server.
[ros2run]: Aborted
4、编写launch文件,加载moveit配置
# create launch
mkdir launch# update CMakeLists.txt
install(DIRECTORYlaunchDESTINATION share/${PROJECT_NAME}/
)
launch文件内容:
# moveit_conf.launch.py
import yaml
import json
from launch import LaunchDescription
from launch.actions import OpaqueFunction
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from uf_ros_lib.moveit_configs_builder import MoveItConfigsBuilderdef launch_setup(context, *args, **kwargs):dof = LaunchConfiguration('dof', default=7)robot_type = LaunchConfiguration('robot_type', default='xarm')prefix = LaunchConfiguration('prefix', default='')hw_ns = LaunchConfiguration('hw_ns', default='xarm')limited = LaunchConfiguration('limited', default=True)effort_control = LaunchConfiguration('effort_control', default=False)velocity_control = LaunchConfiguration('velocity_control', default=False)model1300 = LaunchConfiguration('model1300', default=False)robot_sn = LaunchConfiguration('robot_sn', default='')attach_to = LaunchConfiguration('attach_to', default='world')attach_xyz = LaunchConfiguration('attach_xyz', default='"0 0 0"')attach_rpy = LaunchConfiguration('attach_rpy', default='"0 0 0"')mesh_suffix = LaunchConfiguration('mesh_suffix', default='stl')kinematics_suffix = LaunchConfiguration('kinematics_suffix', default='')add_gripper = LaunchConfiguration('add_gripper', default=False)add_vacuum_gripper = LaunchConfiguration('add_vacuum_gripper', default=False)add_bio_gripper = LaunchConfiguration('add_bio_gripper', default=False)add_realsense_d435i = LaunchConfiguration('add_realsense_d435i', default=False)add_d435i_links = LaunchConfiguration('add_d435i_links', default=True)add_other_geometry = LaunchConfiguration('add_other_geometry', default=False)geometry_type = LaunchConfiguration('geometry_type', default='box')geometry_mass = LaunchConfiguration('geometry_mass', default=0.1)geometry_height = LaunchConfiguration('geometry_height', default=0.1)geometry_radius = LaunchConfiguration('geometry_radius', default=0.1)geometry_length = LaunchConfiguration('geometry_length', default=0.1)geometry_width = LaunchConfiguration('geometry_width', default=0.1)geometry_mesh_filename = LaunchConfiguration('geometry_mesh_filename', default='')geometry_mesh_origin_xyz = LaunchConfiguration('geometry_mesh_origin_xyz', default='"0 0 0"')geometry_mesh_origin_rpy = LaunchConfiguration('geometry_mesh_origin_rpy', default='"0 0 0"')geometry_mesh_tcp_xyz = LaunchConfiguration('geometry_mesh_tcp_xyz', default='"0 0 0"')geometry_mesh_tcp_rpy = LaunchConfiguration('geometry_mesh_tcp_rpy', default='"0 0 0"')moveit_config_dump = LaunchConfiguration('moveit_config_dump', default='')moveit_config_dump = moveit_config_dump.perform(context)moveit_config_dict = yaml.load(moveit_config_dump, Loader=yaml.FullLoader) if moveit_config_dump else {}if not moveit_config_dict:moveit_config = MoveItConfigsBuilder(context=context,# controllers_name=controllers_name,dof=dof,robot_type=robot_type,prefix=prefix,hw_ns=hw_ns,limited=limited,effort_control=effort_control,velocity_control=velocity_control,model1300=model1300,robot_sn=robot_sn,attach_to=attach_to,attach_xyz=attach_xyz,attach_rpy=attach_rpy,mesh_suffix=mesh_suffix,kinematics_suffix=kinematics_suffix,# ros2_control_plugin=ros2_control_plugin,# ros2_control_params=ros2_control_params,add_gripper=add_gripper,add_vacuum_gripper=add_vacuum_gripper,add_bio_gripper=add_bio_gripper,add_realsense_d435i=add_realsense_d435i,add_d435i_links=add_d435i_links,add_other_geometry=add_other_geometry,geometry_type=geometry_type,geometry_mass=geometry_mass,geometry_height=geometry_height,geometry_radius=geometry_radius,geometry_length=geometry_length,geometry_width=geometry_width,geometry_mesh_filename=geometry_mesh_filename,geometry_mesh_origin_xyz=geometry_mesh_origin_xyz,geometry_mesh_origin_rpy=geometry_mesh_origin_rpy,geometry_mesh_tcp_xyz=geometry_mesh_tcp_xyz,geometry_mesh_tcp_rpy=geometry_mesh_tcp_rpy,).to_moveit_configs()moveit_config_dict = moveit_config.to_dict()move_group_interface_params = {'robot_description': moveit_config_dict['robot_description'],'robot_description_semantic': moveit_config_dict['robot_description_semantic'],'robot_description_kinematics': moveit_config_dict['robot_description_kinematics'],}node_executable = LaunchConfiguration('node_executable', default='hello_moveit_planner')node_name = LaunchConfiguration('node_name', default=node_executable)node_parameters = LaunchConfiguration('node_parameters', default={})try:xarm_planner_parameters = json.loads(node_parameters.perform(context))except:xarm_planner_parameters = {}xarm_planner_node = Node(name=node_name,package='hello_moveit',executable=node_executable,output='screen',parameters=[move_group_interface_params,{'robot_type': robot_type,'dof': dof,'prefix': prefix},xarm_planner_parameters,],)# should be a list of nodesreturn [xarm_planner_node]def generate_launch_description():return LaunchDescription([OpaqueFunction(function=launch_setup)])# moveit_api_pose.launch.py
import json
from launch import LaunchDescription
from launch.actions import OpaqueFunction
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.substitutions import FindPackageSharedef launch_setup(context, *args, **kwargs):prefix = LaunchConfiguration('prefix', default='')hw_ns = LaunchConfiguration('hw_ns', default='xarm')limited = LaunchConfiguration('limited', default=False)effort_control = LaunchConfiguration('effort_control', default=False)velocity_control = LaunchConfiguration('velocity_control', default=False)add_gripper = LaunchConfiguration('add_gripper', default=False)add_vacuum_gripper = LaunchConfiguration('add_vacuum_gripper', default=False)dof = LaunchConfiguration('dof', default=6)robot_type = LaunchConfiguration('robot_type', default='xarm')node_executable = 'hello_moveit'node_parameters = {}# moveit conf launch# hello_moveit/launch/moveit_conf.launch.pyrobot_planner_node_launch = IncludeLaunchDescription(PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('hello_moveit'), 'launch', 'moveit_conf.launch.py'])),launch_arguments={'prefix': prefix,'hw_ns': hw_ns,'limited': limited,'effort_control': effort_control,'velocity_control': velocity_control,'add_gripper': 'false','add_vacuum_gripper': add_vacuum_gripper,'dof': dof,'robot_type': robot_type,'node_executable': node_executable,'node_parameters': json.dumps(node_parameters)}.items(),)return [robot_planner_node_launch]def generate_launch_description():return LaunchDescription([OpaqueFunction(function=launch_setup)])
接下来重新编译运行:
# launch rviz
ros2 launch xarm_moveit_config xarm6_moveit_fake.launch.py# launch hello_moveit
ros2 launch hello_moveit moveit_api_pose.launch.py
group name的问题:
# 通过ros2 param查看
ros2 param get /move_group robot_description_semantic
5、add dep: moveit_visual_tools
Visualizing In RViz — MoveIt Documentation: Rolling documentation
在 package.xml
中添加依赖:
# add to package.xml
<depend>moveit_visual_tools</depend>
在CMakeLists.txt
中,补充find_package
,扩展 ament_target_dependencies
宏调用以包含新的依赖项:
find_package(moveit_visual_tools REQUIRED)ament_target_dependencies(hello_moveit"moveit_ros_planning_interface""moveit_visual_tools""rclcpp"
)
在源码中引入头文件:
#include <moveit_visual_tools/moveit_visual_tools.h>
编译验证,发现缺少这个依赖
# 安装依赖
sudo apt-get install ros-$ROS_DISTRO-moveit-visual-tools# 也可使用rosdep,因为已经配置了package.xml
rosdep install --from-paths src --ignore-src -r -y
6、Create a ROS executor and spin the node on a thread
在初始化 MoveItVisualTools 之前,我们需要在 ROS 节点上启动一个执行程序。
(创建一个 ROS 2 执行器,允许在一个线程中处理多个节点的回调。它通过调用 spin()
方法来开始处理来自 ROS 话题、服务、定时器等的消息<阻塞调用>。)
#include <thread> // <---- add this to the set of includes at the top// Spin up a SingleThreadedExecutor for MoveItVisualTools to interact with ROS
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
auto spinner = std::thread([&executor]() { executor.spin(); });// Create the MoveIt MoveGroup Interface
// Shutdown ROS
rclcpp::shutdown(); // <--- This will cause the spin function in the thread to return
spinner.join(); // 等待子线程结束主线程才可结束
return 0;
7、创建并初始化 moveit_visual_tools
接下来,我们将在构造 MoveGroupInterface 之后构造并初始化MoveItVisualTools。构造函数中传入节点、基坐标系、marker topic、机器人模型。
// Create the MoveIt MoveGroup Interface
using moveit::planning_interface::MoveGroupInterface;
auto move_group_interface = MoveGroupInterface(node, "xarm6");// Construct and initialize MoveItVisualTools
// modify base_link to link_base
auto moveit_visual_tools = moveit_visual_tools::MoveItVisualTools{node, "link_base", rviz_visual_tools::RVIZ_MARKER_TOPIC,move_group_interface.getRobotModel()};
moveit_visual_tools.deleteAllMarkers();
moveit_visual_tools.loadRemoteControl();
构建和初始化后,我们现在创建一些闭包(可以访问当前范围内的变量的函数对象),我们稍后可以在程序中使用它们来帮助在 RViz 中呈现可视化。
- 第一个
draw_title
在机器人底座上方一米处添加文本。这是从高级别显示程序状态的有用方法。 - 第二个调用名为
prompt
的函数。此功能会阻止您的程序,直到用户按下 RViz 中的Next
按钮。这对于在调试时单步调试程序很有帮助。 - 第三个绘制轨迹路径。
// Create closures for visualization
auto const draw_title = [&moveit_visual_tools](auto text) {auto const text_pose = [] {auto msg = Eigen::Isometry3d::Identity();msg.translation().z() = 1.0; // Place text 1m above the base linkreturn msg;}();moveit_visual_tools.publishText(text_pose, text, rviz_visual_tools::WHITE,rviz_visual_tools::XLARGE);
};
auto const prompt = [&moveit_visual_tools](auto text) {moveit_visual_tools.prompt(text);
};
auto const draw_trajectory_tool_path =[&moveit_visual_tools,jmg = move_group_interface.getRobotModel()->getJointModelGroup("manipulator")](auto const trajectory) {moveit_visual_tools.publishTrajectoryLine(trajectory, jmg);};
接下来在plan、excute部分都添加触发器。
// Create a plan to that target pose
prompt("Press 'Next' in the RvizVisualToolsGui window to plan");
draw_title("Planning");
moveit_visual_tools.trigger();
auto const [success, plan] = [&move_group_interface] {moveit::planning_interface::MoveGroupInterface::Plan msg;auto const ok = static_cast<bool>(move_group_interface.plan(msg));return std::make_pair(ok, msg);
}();// Execute the plan
if (success) {draw_trajectory_tool_path(plan.trajectory);moveit_visual_tools.trigger();prompt("Press 'Next' in the RvizVisualToolsGui window to execute");draw_title("Executing");moveit_visual_tools.trigger();move_group_interface.execute(plan);
} else {draw_title("Planning Failed!");moveit_visual_tools.trigger();RCLCPP_ERROR(logger, "Planning failed!");
}
8、在rviz中启用可视化
启用rviz,并取消勾选“Motion Planning”,不需要在这部分使用。
# launch rviz
ros2 launch xarm_moveit_config xarm6_moveit_fake.launch.py add_gripper:=True
使用 “Panels/Add New Panel” 添加RvizVisualToolsGui
。
最后,我们需要添加一个 Marker Array
来渲染我们添加的可视化效果。单击 “Displays” 面板中的 “Add” 按钮,并将新 Marker Array /rviz_visual_tools
的主题编辑。
运行验证
9、围绕对象进行规划
创建一个 collision 对象。首先要注意的是它被放置在机器人的坐标系中。如果我们有一个感知系统来报告场景中障碍物的位置,那么它就会构建这种信息。因为这只是一个示例,所以我们是手动创建的。在此代码块的末尾需要注意的一点是,通过设置collision_object.ADD
,这会导致对象被添加到碰撞场景中。将此代码块放在上一步中设置目标姿势和创建Plan之间。
// 添加头文件
#include <moveit/planning_scene_interface/planning_scene_interface.hpp>move_group_interface.setPoseTarget(target_pose);// Create collision object for the robot to avoid
auto const collision_object = [frame_id =move_group_interface.getPlanningFrame()] {moveit_msgs::msg::CollisionObject collision_object;collision_object.header.frame_id = frame_id;collision_object.id = "box1";shape_msgs::msg::SolidPrimitive primitive;// Define the size of the box in metersprimitive.type = primitive.BOX;primitive.dimensions.resize(3);primitive.dimensions[primitive.BOX_X] = 0.5;primitive.dimensions[primitive.BOX_Y] = 0.1;primitive.dimensions[primitive.BOX_Z] = 0.5;// Define the pose of the box (relative to the frame_id)geometry_msgs::msg::Pose box_pose;box_pose.orientation.w = 1.0; // We can leave out the x, y, and z components of the quaternion since they are initialized to 0box_pose.position.x = 0.2;box_pose.position.y = 0.2;box_pose.position.z = 0.25;collision_object.primitives.push_back(primitive);collision_object.primitive_poses.push_back(box_pose);collision_object.operation = collision_object.ADD;return collision_object;
}();prompt("Press 'Next' in the RvizVisualToolsGui window to plan");
draw_title("Planning");
moveit_visual_tools.trigger();// Create a plan to that target pose
auto const [success, plan] = [&move_group_interface]{moveit::planning_interface::MoveGroupInterface::Plan my_plan;auto const ok = static_cast<bool>(move_group_interface.plan(my_plan));return std::make_pair(ok, my_plan);
}();
最后,我们需要将此对象添加到碰撞场景中。为此,我们使用一个名为 PlanningSceneInterface
的对象,它使用 ROS 接口将规划场景的更改传达给 MoveGroup
。此代码块应直接位于创建碰撞对象的代码块之后。
// Add the collision object to the scene
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
planning_scene_interface.applyCollisionObject(collision_object);
编译运行
# launch rviz2
ros2 launch xarm_moveit_config xarm6_moveit_fake.launch.py add_gripper:=Trueros2 launch hello_moveit moveit_api_pose.launch.py
使用moveit任务构造函数实现拾取和放置
Pick and Place with MoveIt Task Constructor — MoveIt Documentation: Rolling documentation
MoveIt任务构造器(MTC)的核心思想是,复杂的运动规划问题可以被分解为一组更简单的子问题。顶层的规划问题被定义为任务,而所有子问题则由阶段来定义。阶段可以按任意顺序和层次结构排列,仅受限于各阶段类型的约束。阶段的排列顺序受结果传递方向的限制。根据结果流的传递方向,存在三种可能的阶段类型:
- 生成器(Generator):独立于相邻阶段计算结果,并向前后两个方向传递结果。例如,用于几何位姿的逆运动学(IK)采样器,其相邻阶段(如接近或离开动作)的解决方案依赖于该阶段的结果。
- 传播器(Propagator):接收一个相邻阶段的结果,求解子问题后,将结果传递给另一侧的相邻阶段。根据具体实现,传播器可以向前、向后或双向传递结果。例如,基于起始状态或目标状态计算笛卡尔路径的阶段。
- 连接器(Connector):不传播结果,而是尝试弥合两个相邻阶段结果状态之间的间隙。例如,计算从给定状态到另一状态的自由运动规划。
除了阶段顺序类型,还存在不同的层次类型,允许封装子阶段:
- 基础阶段(Primitive Stage):不包含子阶段的阶段。
- 容器阶段(Container Stage):包含子阶段的高层阶段。容器阶段分为三种类型:
- 封装容器(Wrapper):封装单个子阶段并修改或过滤其结果。例如,仅接受子阶段满足特定约束解的过滤器阶段。另一种典型应用是逆运动学封装阶段,它基于标注了位姿目标属性的规划场景生成逆运动学解。
- 串行容器(Serial Container):包含一系列子阶段,仅将端到端解决方案视为结果。例如,由多个连贯步骤组成的抓取动作。
- 并行容器(Parallel Container):组合多个子阶段,可用于传递最佳替代结果、运行备用求解器或合并多个独立解。例如,为自由运动规划运行替代规划器、优先用右手抓取物体并设置左手作为备用方案,或同时移动手臂和打开夹爪。
阶段不仅支持解决运动规划问题,还可用于处理各种状态转换(例如修改规划场景)。结合类继承的灵活性,仅需依赖一组结构良好的基础阶段即可构建非常复杂的行为。
1、start
拉取moveit_task_constructor包,安装相关依赖
cd ~/dev_ws/srcgit clone -b $ROS_DISTRO https://github.com/moveit/moveit_task_constructor.gitrosdepc install --from-paths . --ignore-src --rosdistro $ROS_DISTRO# 编译测试
colcon build --mixin release
报错信息
# mixin作用:使用colcon进行编译的时候有时会传入很多cmake-args,或者其他的args,并且还是固定每次都要传入,因此通过mixin提供一个快捷输入这一大串args的方式
dod@qDoDp:~/dev_ws$ colcon build --mixin release
usage: colcon [-h] [--log-base LOG_BASE] [--log-level LOG_LEVEL]{build,extension-points,extensions,graph,info,list,metadata,mixin,test,test-result,version-check}...
colcon: error: Mixin 'release' is not available for 'build'
需要配置mixin
# 已有
sudo apt install python3-colcon-mixin
# 添加mixin源
colcon mixin add default https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml
# 更新源
colcon mixin update default# re build
--- stderr: moveit_task_constructor_core
lto-wrapper: warning: using serial compilation of 12 LTRANS jobs
lto-wrapper: note: see the ‘-flto’ option documentation for more information
---
Finished <<< moveit_task_constructor_core [55.0s]
1 packages had stderr output: moveit_task_constructor_core
2、try demos
MoveIt Task Constructor 包包含几个基本示例和一个拾取和放置演示。对于所有演示,您都应该启动基本环境:
ros2 launch moveit_task_constructor_demo demo.launch.py
随后,您可以运行各个演示:
ros2 launch moveit_task_constructor_demo run.launch.py exe:=cartesian
ros2 launch moveit_task_constructor_demo run.launch.py exe:=modular
ros2 launch moveit_task_constructor_demo run.launch.py exe:=pick_place_demo
在右侧,您应该会看到 Motion Planning Tasks 面板,其中概述了任务的层次结构阶段结构。当您选择特定阶段时,成功和失败的解决方案列表将显示在最右侧的窗口中。选择其中一个解决方案将开始其可视化。
相关文章:
moveit2基础教程上手-使用xarm6演示
0、前置信息 开发环境:wsl。 ros版本:jazzy,ubuntu版本:24.04 xarm-ros2地址 1、启动Rviz,加载 Motion Planning Plugin,实现演示功能 Getting Started — MoveIt Documentation: Rolling documentation…...
头部姿态估计(Head Pose Estimation)领域,有许多开源工具和库可供选择,一些常用的工具及其特点
在头部姿态估计(Head Pose Estimation)领域,有许多开源工具和库可供选择。以下是一些常用的工具及其特点比较: 1. OpenCV 特点: OpenCV 是一个广泛使用的计算机视觉库,提供了丰富的图像处理和计算机视觉算法。虽然 O…...
Qt调用Miniconda的python方法
1、 Win 64环境下载及安装 Miniconda 首先下载Windows 版Miniconda,https://docs.conda.io/en/latest/miniconda.html或 https://repo.anaconda.com/miniconda/ 安装界面及选择如下图所示: 安装完python3.12版报错如下。 说明:python3.11版…...
【Linux 下的 bash 无法正常解析, Windows 的 CRLF 换行符问题导致的】
文章目录 报错原因:解决办法:方法一:用 dos2unix 修复方法二:手动转换换行符方法三:VSCode 或其他编辑器手动改 总结 这个错误很常见,原因是你的 wait_for_gpu.sh 脚本 文件格式不对,具体来说…...
DSP数字信号处理
数字信号处理(Digital Signal Processing,简称DSP)是一门研究如何通过数字技术对信号进行分析、修改和合成的学科。DSP在现代电子系统中无处不在,广泛应用于音频处理、视频处理、通信、雷达、医学成像等领域。 什么是数字信号处理…...
vue3 获取当前路由信息失败问题
刷新浏览器时获取当前路由信息失败:undefined import { ref, reactive, onMounted } from vue; import { useRoute } from vue-router; const route useRoute();onMounted(()>{// 打印当前路由信息console.log(当前route, route ); // 这里的打印有值console.…...
数据驱动进化:AI Agent如何重构手机交互范式?
如果说AIGC拉开了内容生成的序幕,那么AI Agent则标志着AI从“工具”向“助手”的跨越式进化。它不再是简单的问答机器,而是一个能够感知环境、规划任务并自主执行的智能体,更像是虚拟世界中的“全能员工”。 正如行业所热议的:“大…...
汽车芯片成本控制:挑战、策略与未来趋势
一、引言 随着汽车行业的快速发展,汽车芯片在车辆中的应用越来越广泛。从简单的发动机控制单元到复杂的自动驾驶系统,芯片已成为汽车智能化、电动化的核心部件。然而,汽车芯片的高成本一直是制约汽车行业发展的重要因素之一。本文将深入探讨…...
RIP实验
RIP实验 一、实验背景 RIP协议: RIP协议(Routing Information Protocol,路由信息协议)是一种基于距离矢量的内部网关协议,即根据跳数来度量路由开销,进行路由选择。相比于其它路由协议(如OSPF、…...
NAT 实验:多私网环境下 NAPT、Easy IP 配置及 FTP 服务公网映射
NAT基本概念 定义:网络地址转换(Network Address Translation,NAT)是一种将私有(保留)地址转化为合法公网 IP 地址的转换技术,它被广泛应用于各种类型 Internet 接入方式和各种类型的网络中。作…...
电力和冷却管理:如何让数据中心“高效降温”同时节能增效
电力和冷却管理:如何让数据中心“高效降温”同时节能增效 数据中心作为现代信息技术基础设施的核心,承担着处理、存储和传输海量数据的重任。然而,这些庞大的服务器和存储设备在高速运转时,不仅需要大量电力供应,还产生了大量热量。如何平衡电力消耗与有效冷却,成为了数…...
LangChain Chat Model学习笔记
Prompt templates: Few shot、Example selector 一、Few shot(少量示例) 创建少量示例的格式化程序 创建一个简单的提示模板,用于在生成时向模型提供示例输入和输出。向LLM提供少量这样的示例被称为少量示例,这是一种简单但强大的指导生成的方式&…...
嵌入式硬件篇---Keil51中的关键字
文章目录 前言1. 存储类型关键字1.1code作用地址范围用途示例 1.2data作用地址范围用途示例 1.3idata作用地址范围用途示例 1.4xdata作用地址范围用途示例 1.5pdata作用地址范围用途示例 1.6volatile作用用途示例 2. 其他常用关键字2.1bit作用示例 2.2sbit作用示例 2.3sfr / sf…...
《TCP/IP网络编程》学习笔记 | Chapter 20:Windows 中的线程同步
《TCP/IP网络编程》学习笔记 | Chapter 20:Windows 中的线程同步 《TCP/IP网络编程》学习笔记 | Chapter 20:Windows 中的线程同步用户模式和内核模式用户模式同步内核模式同步 基于 CRITICAL_SECTION 的同步内核模式的同步方法基于互斥量对象的同步基于…...
MyBatis 中 #{} 和 ${} 的区别详解
目录 1. #{} 和 ${} 的基本概念 1.1 #{} 1.2 ${} 2. #{} 和 ${} 的工作原理 2.1 #{} 的工作原理 2.2 ${} 的工作原理 3.共同点:动态 SQL 查询 4. 区别:处理方式和适用场景 4.1 处理方式 4.2 适用场景 (1)#{} 的适用场景…...
C++学习之网盘项目单例模式
目录 1.知识点概述 2.单例介绍 3.单例饿汉模式 4.饿汉模式四个版本 5.单例类的使用 6.关于token的作用和存储 7.样式表使用方法 8.qss文件中选择器介绍 9.qss文件样式讲解和测试 10.qss美化登录界面补充 11.QHTTPMULTIPART类的使用 12.文件上传协议 13.文件上传协议…...
Lineageos 22.1(Android 15)制定应用强制横屏
一、前言 有时候需要系统的某个应用强制衡平显示,不管他是如何配置的。我们只需要简单的拿到top的Task下面的ActivityRecord,并判断包名来强制实现。 二、调整wms com.android.server.wm.DisplayRotation /*** Given an orientation constant, return…...
基于deepseek的智能语音客服【第四讲】封装milvus数据库连接池封装
通过工厂模式创建链接 static {// 创建连接池工厂BasePooledObjectFactory<MilvusServiceClient> factory new BasePooledObjectFactory<MilvusServiceClient>() {Overridepublic MilvusServiceClient create() throws Exception {return new MilvusServiceClient…...
【GeeRPC】项目总结:使用 Golang 实现 RPC 框架
文章目录 项目总结:使用 Golang 实现 RPC 框架谈谈 RPC 框架什么是 RPC 框架实现一个 RPC 框架需要什么?项目总结文章结构安排 Part1:消息编码编解码器的实现通信过程 Part2:服务端Accept:阻塞地等待连接请求并开启 go…...
人工智能在医疗影像诊断中的应用与挑战
引言 近年来,人工智能(AI)技术在医疗领域的应用逐渐成为研究热点,尤其是在医疗影像诊断方面。AI技术的引入为医疗影像诊断带来了更高的效率和准确性,有望缓解医疗资源紧张的问题,同时为患者提供更优质的医疗…...
烧结银技术赋能新能源汽车超级快充与高效驱动
烧结银技术赋能新能源汽车超级快充与高效驱动 在新能源汽车领域,高压快充技术的突破与高功率密度驱动系统的创新正成为行业竞争的焦点。比亚迪于 2025 年发布的超级 e 平台,通过整合全域千伏高压架构、兆瓦级闪充技术及碳化硅(SiC࿰…...
大模型幻觉产生的【九大原因】
知识问答推理幻觉产生的原因 1.知识库结构切割不合理 大段落切割向量化 切分太小可以实现更精准化的回复内,向量匹配相似度越高。检索内容碎片化严重、可能包含不符合内容的文本数据。切分太大内容资料更完整,但是会影响相似度,同时更消耗资…...
4小时速通shell外加100例
🔥 Shell 基础——从入门到精通 🚀 🌱 第一章:Shell,简单说! 👶 什么是Shell?它到底能做什么?这章让你快速了解Shell的强大之处! 👶 什么是Shell…...
AD(Altium Designer)更换PCB文件的器件封装
一、确定是否拥有想换的器件PCB封装 1.1 打开现有的原理图 1.2 确定是否拥有想换的器件PCB文件 1.2.1 如果有 按照1.3进行切换器件PCB封装 1.2.2 如果没有 按照如下链接进行添加 AD(Altium Designer)已有封装库的基础上添加器件封装-CSDN博客https://blog.csdn.net/XU15…...
Postgresql 删除数据库报错
1、删除数据库时,报错存在其他会话连接 ## 错误现象,存在其他的会话连接正在使用数据库 ERROR: database "cs" is being accessed by other users DETAIL: There is 1 other session using the database.2、解决方法 ## 终止被删除数据库下…...
人工智能时代——深度探索如何构建开放可控的专利生态体系
# 人工智能时代——深度探索如何构建开放可控的专利生态体系 引言:AI专利革命的战略抉择第一章 战略认知与基本原则1.1 人工智能专利革命的范式重构1.1.1 技术维度变革1.1.2 法律维度挑战1.1.3 文明安全的不可控风险 1.2 战略定位体系构建1.2.1 双循环治理框架的立体…...
✨【数据变形术:联合体在通信协议中的降维打击】✨
(万字长文详解联合体的二进制魔法与工程实践) 🔮 原理解析:内存空间的量子叠加态 文字叙述: 联合体(union)是C语言中最具魔法的数据结构,其所有成员共享同一块内存空间。这种特性使…...
docker compose部署minio报错
背景 部分服务使用docker-compose单节点编排,其中对象存储服务使用minio,在minio中配置了aksk后报错 Error: IAM sub-system is partially initialized, unable to write the IAM forma 解决 minio如果配置了aksk等iam类的配置则需要持久化存储到etcd…...
软件开发通用之状态机初认识-基本概念及简单应用
0 前言 在程序开发阶段(其实也不限于程序,还包含硬件电路设计,协议设计等),无论使用何种语言,何种工具,何种系统,程序的运行必须符合开发者的预设逻辑,而单独通过大脑记…...
蓝桥杯 之 第27场月赛总结
文章目录 习题1.抓猪拿国一2.蓝桥字符3.蓝桥大使4.拳头对决 习题 比赛地址 1.抓猪拿国一 十分简单的签到题 print(sum(list(range(17))))2.蓝桥字符 常见的字符匹配的问题,是一个二维dp的问题,转化为对应的动态规划求解 力扣的相似题目 可以关注灵神…...
适配器模式 (Adapter Pattern)
适配器模式 (Adapter Pattern) 是一种结构型设计模式,它将一个类的接口转换成客户希望的另外一个接口,使得原本由于接口不兼容而不能一起工作的类可以一起工作。 在现实生活中,适配器的例子随处可见,比如电源适配器,它将不同电压的电流转换为设备所需的电压,确保设备能正…...
操作系统WIN11无法出现WLAN图标(解决方案)
本人操作系统WIN11之后无网络图标 于是在设置里查看了一下,是网卡驱动没了 网上去下载一个驱动类软件自行处理即可。 本人使用手机USB网络连的电脑,然后发现网卡驱动凭空出现了,就很困惑,没有下载驱动就恢复了。...
HCL—我与虚拟机的爱恨情仇[特殊字符][特殊字符][特殊字符]️
时隔了三周,我可能算是了解了虚拟机了吧。自从上一次的安装虚拟机,我与HCL、虚拟机就没有停止过纠缠。 为什么很多win11电脑使用不了HCL,或者无法启动HCL设备? 首先来解答,为什么很多win11电脑使用不了HCL,…...
illustrate:一款蛋白/核酸结构快速渲染为“卡通风格”的小工具
本期向大家介绍一款蛋白/核酸结构快速渲染(卡通风格)的小工具——illustrate。放心!本期完全不涉及代码,不折腾人,请放心食用。 结构渲染效果示例如下: PDB ID: 1ttt 该小工具适用绘制蛋白或复合物整体轮廓…...
Linux上位机开发实战(能用的开发板计算资源)
【 声明:版权所有,欢迎转载,请勿用于商业用途。 联系信箱:feixiaoxing 163.com】 大家所能想到的嵌入式上位机开发,如果是linux,同时涉及到嵌入式的话,一般都会认为是把pc linux的软件port到板子…...
kotlin 内联函数 inline
高阶函数实现的原理:函数类型其实是生成了一个对象 。 inline翻译成中文的意思就是内联,在kotlin里面inline被用来修饰函数,表明当前函数在编译时是以内嵌的形式进行编译的,从而减少了一层函数调用栈: inline fun fun…...
vue3配置代理实现axios请求本地接口返回PG库数据【前后端实操】
前端编写 安装 axios 如果当前未安装axios,可以执行如下指令安装 npm install axios配置代理 当前为基于Vite构建的项目,在 vite.config.ts 中配置代理,在defineConfig中新增server配置,主要关注两个点: 一、需要代…...
论文阅读:2023 arxiv Multiscale Positive-Unlabeled Detection of AI-Generated Texts
总目录 大模型安全相关研究:https://blog.csdn.net/WhiffeYF/article/details/142132328 Multiscale Positive-Unlabeled Detection of AI-Generated Texts https://arxiv.org/abs/2305.18149 https://www.doubao.com/chat/2114270649152258 https://github.com/YuchuanTi…...
【数学建模】最大最小值模型详解
数学建模中的最大最小值模型详解 文章目录 数学建模中的最大最小值模型详解引言最大最小值模型的基本概念最大化问题最小化问题 常见的求解方法1. 微积分法2. 线性规划3. 非线性规划4. 动态规划 实际应用案例案例1:生产规划问题案例2:投资组合优化 最大最…...
Camera2 实现重力感应四个方向调试相机预览
Camera2API 实现重力感应四个方向调试相机预览 文章目录 需求场景 需求实现setAspectRatio 设置显示长宽postScale postRotate 设置缩放和旋转manager.openCamera 打开相机startPreviewgetPreviewRequestBuilder 设置预览参数:createCaptureSession 预览准备工作set…...
C++::多态
目录 一.多态的概念 二.多态的定义及实现 二.1多态的构成条件 二.2虚函数 1.虚函数的写法 2.虚函数的重写/覆盖 3.协变 二.3析构函数的重写 二.4override和final关键字 编辑二.5重载/重写/隐藏的对比 三.多态的运行原理(一部分) 四.多态的常…...
278.缀点成线
1232. 缀点成线 - 力扣(LeetCode) class Solution {public boolean checkStraightLine(int[][] coordinates) {if(coordinates.length2){return true;}int xcoordinates[1][0]-coordinates[0][0];int ycoordinates[1][1]-coordinates[0][1];for(int i1;i…...
xssgame第8关注入详解
1.SVG利用实现xss攻击 1.代码如下: <!DOCTYPE html> <html lang"en"> <head><meta charset"UTF-8"><meta name"viewport" content"widthdevice-width, initial-scale1.0"><title>tes…...
《数据库原理》SQLServer期末复习_题型+考点
目录 题型: 一. 概况分析题(5小题,每小题2分,共10分) 二. 计算题(3小题,每小题5分,共15分) 三. 数据库设计(2小题,每小题10分,共2…...
RK3588开发笔记-RTL8852wifi6模块驱动编译报错解决
目录 前言 一、问题背景 二、驱动编译 总结 前言 在基于 RK3588 进行开发,使用 RTL8852 WiFi6 模块时,遇到了一个让人头疼的驱动编译报错问题:“VFs_internal_I_am_really_a_filesystem_and_am_NoT_a_driver, but does”。经过一番摸索和尝试,最终成功解决了这个问题,在…...
机器学习算法实战——天气数据分析(主页有源码)
✨个人主页欢迎您的访问 ✨期待您的三连 ✨ ✨个人主页欢迎您的访问 ✨期待您的三连 ✨ ✨个人主页欢迎您的访问 ✨期待您的三连✨ 1. 引言 天气数据分析是气象学和数据科学交叉领域的一个重要研究方向。随着大数据技术的发展,气象数据的采集、存储和分…...
java项目之基于ssm的毕业论文管理系统(源码+文档)
项目简介 毕业论文管理系统实现了以下功能: 本毕业论文管理系统主要实现的功能模块包括学生模块、导师模块和管理员模块三大部分,具体功能分析如下: (1)导师功能模块:导师注册登录后主要功能模块包括个人…...
【Vue3入门1】02- vue3的基本操作(上)
本文介绍vue3中的一些方法的操作。 目录 1. 绑定事件 v-on 2. 按键修饰符 3. 显示和隐藏 v-show 4. 条件渲染 v-if 5. 条件渲染if-else 1. 绑定事件 v-on 点击事件 v-on:click" 发生事件 " <body><div id"app">{{ msg }} <h2&g…...
Redis集群搭建和高可用方案(Java实现)
Redis集群搭建和高可用方案(Java实现) 我将详细介绍如何使用Java技术搭建Redis集群并实现高可用方案。 1. Redis集群架构概述 Redis集群可以通过以下几种方式实现: 主从复制Sentinel哨兵模式Redis Cluster集群模式2. 使用Java实现Redis集群连接 2.1 使用Jedis客户端 Je…...
【大模型算法工程】大模型应用工具化、忠诚度以及知识库场景下PDF双栏解析问题的讨论
1. 大模型时代应用工具化以及无忠诚度现象讨论 接触大模型久了,也慢慢探到一些大模型能力表现非常自然和突出的场景,比如AI搜索(依赖大模型的理解总结能力)、AI对话(即chat,依赖大模型的生成能力࿰…...