Autoware.universe部署06:使用DBC文件进行UDP的CAN通信代码编写

目录标题

  • 一、安装DBC文件编辑工具VectorCANdb++
  • 二、编写DBC文件
    • 2.1 CAN通信协议
    • 2.2 编写DBC文件
      • 2.2.1 根据CAN协议设置signals
      • 2.2.2 设置报文
      • 2.2.3 建立节点
  • 三、根据DBC文件编写ROS2驱动程序
  • 四、实际通信调试


根据CAN协议编写DBC文件,通过DBC文件编写ROS2包进行UDP通信,获取底盘速度转发至Autoware.Universe以及订阅Autoware.Universe控制命令,下发至CAN控制底盘运动(本文适用于CAN盒通过网线连接进行UDP通信),本系列其他文章:
Autoware.universe部署01:Ubuntu20.04安装Autoware.universe并与Awsim联调
Autoware.universe部署02:高精Lanelet2地图的绘制
Autoware.universe部署03:与Carla(二进制版)联调
Autoware.universe部署04:universe传感器ROS2驱动
Autoware.universe部署05:实车调试

一、安装DBC文件编辑工具VectorCANdb++

windows系统下安装VectorCANdb++,下载链接:https://www.vector.com/cn/zh/download/candb-31-sp3/
在这里插入图片描述
下载完成后常规安装,选择安装路径,其他过程一路Next:
在这里插入图片描述
安装完成后在左下角程序列表中可以找到

二、编写DBC文件

2.1 CAN通信协议

下面是松灵的HUNTER SE通信协议,是一款阿克曼模型可编程UGV( UNMANNED GROUND VEHICLE ),它是一款采用阿克曼转向设计的底盘。下面只列举了三帧数据,每一帧数据包含一系列字节(例如:0x01, 0x11, 0x00,0x96, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00)的数据,我们需要注意的是每一帧数据的发送与接收节点,帧ID(例如:0x01, 0x11),数据长度,以及功能数据(例如:0x00,0x96, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00):
在这里插入图片描述
在这里插入图片描述
在这里插入图片描述

2.2 编写DBC文件

有了通讯协议之后,打开VectorCANdb++,点击File->Create Database->CANTemplate.dbc后点击OK,创建文件名:
在这里插入图片描述

2.2.1 根据CAN协议设置signals

点击signals->new
在这里插入图片描述
以运动回馈帧的数据为例,根据上面的通讯协议数据帧包含8个字节byte,即8个信号signals,每个字节signals包含8个比特bit,协议中第3、4、5、6个字节没有定义数据,就默认为0,以速度高位为例:

  • Value Type高位选择有符号数据signed,低位选择无符号选择Unsigned
  • Length(信号bit长度)8
  • Factor(数据精度)一般为1
  • Minimum与Maximum根据表格来填,表格是-4800~4800包含的是两位数据,这里单个信号是不一样的。协议中给出的是十六进制数,而这边的最大值最小值范围是十进制数,转化一下:如果是有符号的字节符号占一位,那么转化成十进制就是-127~127,如果是无符号的就是0~255。如果要遵守协议即-4800~4800,那么高位最好写成-18~18『(4800-256)/256=17.5』,写大一点没问题
    在这里插入图片描述
    在这里插入图片描述
    按照协议写好所有的信号如下:
    在这里插入图片描述

2.2.2 设置报文

在Messages下新建报文:注意帧ID以及数据字节数
在这里插入图片描述
之后建立报文与信号的关系,鼠标左键按住设置好的signals,拖动到新建的Messages上面,注意顺序要与协议文件中顺序一致
在这里插入图片描述
如果顺序错了,双击signals设置开始bit数可以更改
在这里插入图片描述
全都拖好了,双击新建的Messages,然后点击Layout,如下图所示,可以检查一下报文设置是否正确(图片上的字节顺序,从右至左,从上到下,依次增大)
在这里插入图片描述

2.2.3 建立节点

(1)建立发送和接受节点
右键点击Network nodes -> New,只需输入创建的网络节点名字进行新建操作
(2)需要发送的报文直接拖到目标节点下的Tx Messages下面即可
(3)需要接收的报文添加:双击打开Receive,选择Mapped Rx Sig.,然后选择Add:all from one message添加我们建立的报文,会将信号添加如下:
在这里插入图片描述
检查节点间的收发关系:在”View”中选择”Communication Matrix…”,可以看到各个节点的收发信号:
在这里插入图片描述
在”File”中选择”Consistency Check”,此时会在一致性检查窗口中输出检查结果。会有状态信息及对应的说明,以供我们检查出错/警告报警的原因。下面是我们建立的没有问题的dbc
在这里插入图片描述
编写完成后即可保存,其内容如下:

VERSION ""NS_ : NS_DESC_CM_BA_DEF_BA_VAL_CAT_DEF_CAT_FILTERBA_DEF_DEF_EV_DATA_ENVVAR_DATA_SGTYPE_SGTYPE_VAL_BA_DEF_SGTYPE_BA_SGTYPE_SIG_TYPE_REF_VAL_TABLE_SIG_GROUP_SIG_VALTYPE_SIGTYPE_VALTYPE_BO_TX_BU_BA_DEF_REL_BA_REL_BA_DEF_DEF_REL_BU_SG_REL_BU_EV_REL_BU_BO_REL_SG_MUL_VAL_BS_:BU_: Base_CAN Base ControlBO_ 1057 Control_mode: 1 ControlSG_ Control_mode : 0|1@1+ (1,0) [0|1] ""  BaseBO_ 273 Motion_Control: 8 ControlSG_ Steer_Angle_control_L : 56|8@1+ (1,0) [0|255] ""  BaseSG_ Steer_Angle_control_H : 48|8@1- (1,0) [-127|127] ""  BaseSG_ Stay_7 : 40|8@1- (1,0) [0|0] ""  BaseSG_ Stay_6 : 32|8@1- (1,0) [0|0] ""  BaseSG_ Stay_5 : 24|8@1- (1,0) [0|0] ""  BaseSG_ Stay_4 : 16|8@1- (1,0) [0|0] ""  BaseSG_ Velocity_control_Low : 8|8@1+ (1,0) [0|255] ""  BaseSG_ Velocity_control_High : 0|8@1- (1,0) [-127|127] ""  BaseBO_ 545 Motion_Feedback: 8 Base_CANSG_ Steer_Angle_L : 56|8@1+ (1,0) [0|255] ""  ControlSG_ Steer_Angle_H : 48|8@1- (1,0) [-127|127] ""  ControlSG_ Stay_3 : 40|8@1- (1,0) [0|0] ""  ControlSG_ Stay_2 : 32|8@1- (1,0) [0|0] ""  ControlSG_ Stay_1 : 24|8@1- (1,0) [0|0] ""  ControlSG_ Stay_0 : 16|8@1- (1,0) [0|0] ""  ControlSG_ Velocity_Low : 8|8@1+ (1,0) [0|255] ""  ControlSG_ Velocity_High : 0|8@1- (1,0) [-127|127] ""  ControlBA_DEF_  "MultiplexExtEnabled" ENUM  "No","Yes";
BA_DEF_  "BusType" STRING ;
BA_DEF_DEF_  "MultiplexExtEnabled" "No";
BA_DEF_DEF_  "BusType" "CAN";

重点关注报文以及信号:

报文格式:
BO_ MessageId MessageName: MessageSize TransmitterMessageId 			为10进制表示的报文ID,类型为longlogn型,即CAN IDMessageName 		报文的名字,与C语言命令规范相同MessageSize 		报文数据段字节数Transmitter 		该报文的网络节点,如果该报文没有指定发送节点,则该值需设置为”Vector__XXX”举例:
以下是DBC中代表一条消息的描述信息
BO_ 545 Motion_Feedback: 8 Base_CAN解释
BO_								代表一条消息的起始标识
545  							消息ID的十进制形式,=0x3f7
Motion_Feedback					消息名
8								消息报文长度,帧字节数
Base_CAN						发出该消息的网络节点,标识为Vector__XXX时未指明具体节点
信号格式
SG_ SignalName (SigTypeDefinition) : StartBit|SignalSize@ByteOrder ValueType (Factor,Offset) [Min|Max] Unit ReceiverSignalName (SigTypeDefinition) 	表示该信号的名字 和 多路选择信号的定义SigTypeDefinition	是可选项,有3种格式:a> 空b> M 表示多路选择器信号c> m50 表示被多路选择器选择的信号,50表示当‘M’定义的信号的值等于50的时候,该报文使用此通路StartBit|SignalSize 表示该信号的起始位及信号长度ByteOrder 	表示信号的字节顺序:0代表Motorola格式,1代表Inter格式ValueType 	表示该信号的数值类型:+表示无符号数,-表示有符号数Factor,Offset 	表示因子,偏移量;这两个值用于信号的原始值与物理值之间的转换。 转换公式:物理值=原始值*因子+偏移量Min|Max 	表示该信号的最小值和最大值,即指定了该信号值的范围;这两个值为double类型Unit 	表示该信号的物理单位,为字符串类型Receiver 表示该信号的接收节点(可以是多个节点);若该信号没有指定的接收节点,则必须设置为” Vector__XXX”举例:
每条报文消息里面有多个报文信号,报文信号的信息的起始标识为"SG_", 
它以一个"BO_"开始至下一"BO_"之间的内容止,详细报文消息以缩进1或2个空格符形式类似树图子节点的方式呈现。
一条消息下的一个信号的信息,此处缩进一个空格SG_ Steer_Angle_L : 56|8@1+ (1,0) [0|255] ""  Control解释:
SG_							代表一个信号信息的起始标识
Steer_Angle_L	     	 	信号名,分长名与短名,此处是短名。长名非必须存在,可以不定义
56							信号起始bit
|							分割符号
8							信号总bit长度
@1+							@0表示是Motorola格式(Intel格式是1),+表示是无符号数据
(1,0)						(精度值,偏移值)
[0|255]						[最小值|最大值], 物理意义的最小与最大,现实世界的有物理意义的值,比如此处仪表续航里程最大999KM
""						"单位"
Control						接收处理此信号的节点,同样可以不指明,写为Vector__XXX

三、根据DBC文件编写ROS2驱动程序

在得到了dbc文件之后,即可调用cantools库进行UDP通信的程序编写

pip3 install cantools==39.0.0

参考栏目其他文章,Autoware.universe需要接收底盘反馈的速度/vehicle/status/velocity_status等消息,同时发送自定义的速度控制消息twist_cmd_feedback到底盘以控制小车运动,代码编写如下:

# -*- coding: utf-8 -*-
import math
import time
import socket
import cantools
import threading
import rclpy
from rclpy.node import Node
from builtin_interfaces.msg import Time
from binascii import hexlify
from geometry_msgs.msg import TwistStamped, Twist
from autoware_auto_control_msgs.msg import AckermannControlCommand
from autoware_auto_vehicle_msgs.msg import ControlModeReport, GearReport, SteeringReport, VelocityReport# 创建UDP socket套接字
# AF_INET表示使用ipv4,默认不变,SOCK_DGRAM表示使用UDP通信协议
udp_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)# 绑定UDP的本机端口port
local_addr = ("192.168.1.102", 8882)  # 本地ip,端口号
udp_socket.bind(local_addr)  # 绑定端口# 指定要接收的前五个字节的CAN协议数据
EXPECTED_DATA = bytes([0x08, 0x00, 0x00, 0x02, 0x11])# 控制小车以0.15m/S的速度前进(0x96->150mm/s,150/100=0.15m/s)
test1 = bytes([0x08, 0x00, 0x00, 0x01, 0x11, 0x00,0x96, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00])
# 控制小车转向0.2rad(0xC8->200x0.001rad->0.2rad)
test2 = bytes([0x08, 0x00, 0x00, 0x01, 0x11, 0x00,0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xC8])# 运动控制消息
data_Control_mode = {'Velocity_control_High': 0, 'Velocity_control_Low': 0,'Stay_4': 0, 'Stay_5': 0, 'Stay_6': 0, 'Stay_7': 0,'Steer_Angle_control_H': 0, 'Steer_Angle_control_L': 0}# 运动反馈消息
data_Motion_Feedback = {'Velocity_High': 32, 'Velocity_Low': 0,'Stay_0': 0, 'Stay_1': 0, 'Stay_2': 0, 'Stay_3': 0,'Steer_Angle_H': 0, 'Steer_Angle_L': 0, }# Control_mode的帧信息与帧ID
message_Control_mode_front = bytes([0x08, 0x00, 0x00, 0x01, 0x11])# ---------------------------------------------------------接收底盘数据
def calculate_speed(linear_speed):# 根据通讯协议将线速度m/s转化为int16的高低位# 车体行进速度,单位mm/s(有效值+ -4800)if linear_speed >= 0:if linear_speed > 4.8:linear_speed = 4.8Speed_H, Speed_L = divmod(int(linear_speed * 1000), 256)data_Control_mode['Velocity_control_Low'] = Speed_Ldata_Control_mode['Velocity_control_High'] = Speed_Helse:if linear_speed < -4.8:linear_speed = -4.8Speed_H, Speed_L = divmod(int(-linear_speed * 1000), 256)data_Control_mode['Velocity_control_Low'] = Speed_L# 设置最高位为1表示负数data_Control_mode['Velocity_control_High'] = 0x80 | Speed_H# print('EV_Speed_H:%f' % EV_Speed_H)# print('EV_Speed_L:%f' % EV_Speed_L)def calculate_angle(linear_speed, angular_speed):# 转向内转角角度单位:0.001rad (有效值+-400)# 转弯的角度 = arctan(( 角速度 / 线速度 ) * 车长 )Steer_Angle = math.atan((angular_speed/linear_speed) * 1)# print('Steer_Angle:%f' % Steer_Angle)if Steer_Angle >= 0:if Steer_Angle > 0.4:Steer_Angle = 0.4Steer_Angle_H, Steer_Angle_L = divmod(int(Steer_Angle * 1000), 256)data_Control_mode['Steer_Angle_control_L'] = Steer_Angle_Ldata_Control_mode['Steer_Angle_control_H'] = Steer_Angle_Helse:if linear_speed < -0.4:linear_speed = -0.4Steer_Angle_H, Steer_Angle_L = divmod(int(-Steer_Angle * 1000), 256)data_Control_mode['Steer_Angle_control_L'] = Steer_Angle_L# 设置最高位为1表示负数data_Control_mode['Steer_Angle_control_H'] = 0x80 | Steer_Angle_Hdef calculate_angle(Steer_Angle):# print("Steer_Angle:", Steer_Angle)if Steer_Angle >= 0:if Steer_Angle > 0.4:Steer_Angle = 0.4Steer_Angle_H, Steer_Angle_L = divmod(int(Steer_Angle * 1000), 256)data_Control_mode['Steer_Angle_control_L'] = Steer_Angle_Ldata_Control_mode['Steer_Angle_control_H'] = Steer_Angle_Helse:if linear_speed < -0.4:linear_speed = -0.4Steer_Angle_H, Steer_Angle_L = divmod(int(-Steer_Angle * 1000), 256)data_Control_mode['Steer_Angle_control_L'] = Steer_Angle_L# 设置最高位为1表示负数data_Control_mode['Steer_Angle_control_H'] = 0x80 | Steer_Angle_H# udp向底盘发送can协议
def udp_send_can(message_name):# 底盘ip和端口号udp_socket.sendto(message_name, ("192.168.1.10", 6666))# 处理接收到的CAN消息的函数
def process_can_message(data, node):# 解码CAN消息can_data = list(data[5:])  # 从第6个字节开始是CAN数据message = node.db.decode_message("Motion_Feedback", can_data)# 打印解码结果# print(message)# print('Steer_Angle_L:', message['Steer_Angle_L'])# print('Steer_Angle_H:', message['Steer_Angle_H'])# print('DM_Speed_L:', message['Velocity_Low'])# print('DM_Speed_H:', message['Velocity_High'])# 处理CAN中接收到的数据,转化成线速度和角速度feedback_twist_linear_x = (message['Velocity_High'] * 256 + message['Velocity_Low']) / 1000Steer_Angle = (message['Steer_Angle_H'] * 256 +message['Steer_Angle_L'] ) / 1000# 角速度 = tan(转向角度) * 线速度 / 前后轮轴距feedback_twist_angular_z = math.tan(Steer_Angle) * feedback_twist_linear_x / 1# 发布处理后的Twist消息到另一个话题node.publish_data(feedback_twist_linear_x, feedback_twist_angular_z)node.pubilsh_control_mode(1)node.pubilsh_gear(2)node.pubilsh_steering(Steer_Angle)node.pubilsh_velocity("base_link", feedback_twist_linear_x, 0.0, 0.0)# 接收数据的线程函数
def receive_data(node):while rclpy.ok():# 一帧指令有多少字节data, addr = udp_socket.recvfrom(13)# print(hexlify(data).decode('ascii'))# 确保接收到的数据满足预期的CAN数据if data[:5] == EXPECTED_DATA:# 在新的线程中处理CAN消息,以保证实时性threading.Thread(target=process_can_message,args=(data, node)).start()# -----------------------------------------------------------控制底盘
class TopicSubscriberPublisher(Node):def __init__(self):super().__init__('cmd_vel_to_can_hunter')# 加载dbc文件self.declare_parameter("dbc_hunter")dbcfile = self.get_parameter("dbc_hunter").get_parameter_value().string_valueself.db = cantools.database.load_file(dbcfile)# CAN指令模式:08 00 00 04 21 01self.can_command = bytes([0x08, 0x00, 0x00, 0x04, 0x21, 0x01])self.subscriber = self.create_subscription(AckermannControlCommand, 'control/command/control_cmd', self.sub_callback, 10)self.publisher_data = self.create_publisher(Twist, 'twist_cmd_feedback', 10)self.publisher_control_mode = self.create_publisher(ControlModeReport, '/vehicle/status/control_mode', 10)self.publisher_gear = self.create_publisher(GearReport, '/vehicle/status/gear_status', 10)self.publisher_steering = self.create_publisher(SteeringReport, '/vehicle/status/steering_status', 10)self.publisher_velocity = self.create_publisher(VelocityReport, '/vehicle/status/velocity_status', 10)# self.get_logger().info('TopicSubscriberPublisher node initialized')def sub_callback(self, msg):# 1. 发送CAN指令模式:08 00 00 04 21 01udp_send_can(self.can_command)# 2. 接收autoware传来的线速度和角速度Speed = msg.longitudinal.speed# angular_velocity = msg.lateral.steering_tire_rotation_rateangular_rad = msg.lateral.steering_tire_angle# print('angular_velocity:%f' % angular_velocity)# print('angular_rad:%f' % angular_rad)# 3. 计算速度、角度calculate_speed(Speed)# calculate_angle(1, angular_velocity)calculate_angle(Speed, angular_rad)# 4. 发送can消息message_Motion_Control = self.db.encode_message("Motion_Control", data_Control_mode)message_linear_velocity = message_Control_mode_front + message_Motion_Control# print(hexlify(message_linear_velocity).decode('ascii'))udp_send_can(message_linear_velocity)def publish_data(self, data1, data2):msg = Twist()msg.linear.x = data1msg.angular.z = data2self.publisher_data.publish(msg)def pubilsh_control_mode(self, data):msg = ControlModeReport()msg.mode = dataself.publisher_control_mode.publish(msg)def pubilsh_gear(self, data):msg = GearReport()msg.report = dataself.publisher_gear.publish(msg)def pubilsh_steering(self, data):msg = SteeringReport()msg.steering_tire_angle = dataself.publisher_steering.publish(msg)def pubilsh_velocity(self, data1, data2, data3, data4):msg = VelocityReport()# 获取当前时间# 秒sec_ = int(time.time())# 纳秒nanosec_ = int((time.time()-sec_)*1e9)msg.header.stamp = Time(sec=sec_, nanosec=nanosec_)msg.header.frame_id = data1msg.longitudinal_velocity = data2msg.lateral_velocity = data3msg.heading_rate = data4self.publisher_velocity.publish(msg)def main():# 初始化rclpy.init()# 新建一个节点node = TopicSubscriberPublisher()# 启动接收CAN数据的线程threading.Thread(target=receive_data, args=(node,)).start()# 在CAN指令模式下,需要保证0X111指令帧以小于500MS的周期(建议周期20MS)发送,否则HUNTER# SE会判定为控制信号心跳丢失而进入报错(0X211反馈上层通讯失联),系统报错后会进入待机模式# 保持节点运行,检测是否收到退出指令(Ctrl+C)rclpy.spin(node)# 清理并关闭ros2节点node.destroy_node()rclpy.shutdown()if __name__ == '__main__':main()

编写setup.py和launch文件

from setuptools import setuppackage_name = 'can_ros2_bridge'setup(name=package_name,version='0.0.0',packages=[package_name],# 安装文件至installdata_files=[('share/ament_index/resource_index/packages',['resource/' + package_name]),('share/' + package_name, ['package.xml']),('share/' +package_name, ['launch/can_hunter.launch.py']),('share/' +package_name, ['config/Hunter.dbc']),],install_requires=['setuptools'],zip_safe=True,maintainer='car',maintainer_email='car@todo.todo',description='TODO: Package description',license='TODO: License declaration',tests_require=['pytest'],# 可执行文件entry_points={'console_scripts': ['cmd_vel_to_can_hunter = can_ros2_bridge.send_message_hunter:main',],},
)
from launch import LaunchDescription
from launch_ros.actions import Node
import os
from ament_index_python.packages import get_package_share_directorydef generate_launch_description():# 去install找配置文件config_hunter = os.path.join(get_package_share_directory('can_ros2_bridge'),'Hunter.dbc')can_ros2_bridge = Node(package='can_ros2_bridge',executable='cmd_vel_to_can_hunter',name='can',parameters=[{'dbc_hunter': config_hunter}],output="both")return LaunchDescription([can_ros2_bridge,])

四、实际通信调试

上述代码中,有两个需要注意的,分别是主机和CAN盒的IP以及端口,CAN盒的IP以及端口是固定的(可能需要在上位机中修改),可以在盒子上看到,需要设置本机IP与CAN盒在同一局域网下,例如CAN盒的是"192.168.1.10", 6666,那么设置主机静态IP,最后一位不同即可:
在这里插入图片描述
接着安装wireshark网络调试工具:

sudo apt-get install wireshark

然后打开wireshark

sudo wireshark

可以看到底盘反馈的数据:6666->8882端口,192.168.4.101->192.168.4.101(图不是我的因此IP不一样,关键是数据传输路线)
在这里插入图片描述
数据通了之后修改代码IP和端口,即可实现CAN通信

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

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

相关文章

jetpack compose中实现丝滑的轮播图效果

写在前面 最近在翻Jetpack库&#xff0c;发现了DataStore&#xff0c;官方是这么说的&#xff1a; Jetpack DataStore 是一种数据存储解决方案&#xff0c;允许您使用协议缓冲区存储键值对或类型化对象。DataStore 使用 Kotlin 协程和 Flow 以异步、一致的事务方式存储数据。 …

laravel引入element-ui后,blade模板中使用elementui时,事件未生效问题(下载element-ui到本地直接引入项目)

背景 重构公司后台项目&#xff0c;使用了dcat-admin&#xff0c;但是dcat-admin有些前端功能不能满足需求。因此引入element-ui进行相关界面的优化 具体流程 1.下载element-ui到本地 2.进入如下目录 打开 node_modules\element-ui\lib 复制index.js 打开 node_modules/ele…

[Linux] shell条件语句和if语句

一、条件语句 1.1 测试 test 测试文件的表达式是否成立 格式&#xff1a;test 条件表达式 [ 条件表达式 ] 选项作用-d测试是否为目录-e测试目录或文件是否存在-a测试目录或文件是否存在-f测试是否为文件-r测试当前用户是否有权限读取-w测试当前用户是否有权限写入-x测试当前…

一键合并多个TXT文本,将保存在TXT的快递单号进行一键合并

如果你需要处理大量的TXT文本文件&#xff0c;那么你可能会遇到需要将这些文件合并为一个文件的情况。这不仅涉及到文件的组织和管理&#xff0c;还可能涉及到文件内容的连贯性和完整性。现在&#xff0c;我们有一个强大的工具&#xff0c;可以帮助你轻松实现一键文件整理&…

PCB抄板的一些方法

PCB抄板的技术实现过程简单来说&#xff0c;就是先将要抄板的电路板进行扫描&#xff0c;记录详细的元器件位置&#xff0c;然后将元器件拆下来做成物料清单&#xff08;BOM&#xff09;并安排物料采购&#xff0c;空板则扫描成图片经抄板软件处理还原成pcb板图文件&#xff0c…

私域电商模式全解析:掌握这些方法,让你的生意不再难做!

私域电商是指利用微信、QQ等社交平台将客户流量转化和沉淀&#xff0c;并促使其进行重复购买的电商模式。私域电商具备两个主要特点&#xff0c;分别是“私域”和“电商”。 “私域”指的是将客户添加为好友&#xff0c;并利用微信、QQ、微博等社交平台进行联系和营销的模式。…

智能座舱架构与芯片 - (1) 背景篇

一、软件定义汽车 1.1 什么是软件定义汽车 软件定义汽车(Software Defined Vehicles, SDV)的核心思想是&#xff0c;决定未来汽车的是人工智能为核心的软件技术&#xff0c;而不再是汽车的马力大小&#xff0c;是否真皮座椅&#xff0c;机械性能的好坏。软件定义汽车的终极目…

Servlet实现一个简单的表白墙网站

文章目录 前言效果展示事前准备HTML、CSS、JavaScript分别负责哪些HTML和CSS构架出页面的基本结构和样式JavaScript 实现行为和交互实现服务器端的业务代码整理pom.xmlweb.xmlmessageWall.htmlMessageServlet.java 前言 前面我们学习了 Java 中知名的 HTTP 服务器 tomcat 的安…

栈的生长方向不总是向下

据我了解&#xff0c;栈的生长方向向下&#xff0c;内存地址由高到低 测试 windows下&#xff1a; 符合上述情况 测试Linux下&#xff1a; 由此可见&#xff0c;栈在不同操作系统环境下&#xff0c;生长方向不总是向下

t检验(连续变量)和卡方检验(分类变量)

目录 情形 不同种类的萼片差异 数据类型查看&#xff1a; 差异分析&#xff1a; 不同萼片的种类差异 数据准备 二分类卡方检验 绘图 情形 &#xff1a;当有两列数据进行分析比较时&#xff0c;一列为连续变量&#xff0c;一列数据为分类变量。 rm(list ls()) libra…

智能交通收费RFID读写器在不停车收费(ETC)系统中的应用

随着公路收费规模的不断扩大&#xff0c;传统的人工收费效率低下&#xff0c;收费没有监督&#xff0c;导致票款流失严重甚至还有车辆非法逃票。为了解决这些问题&#xff0c;引入了RFID等多种技术的新型的收费系统-不停车收费(ETC)系统应运而生。 电子不停车收费系统(ETC)系统…

电商平台API接口的作用到底是什么?重要性又是什么?具体接入方式?

电商平台API接口的重要性及其作用主要体现在以下几个方面&#xff1a; 数据支持&#xff1a;电商平台拥有大量的商品信息、用户信息、交易信息等大数据资产&#xff0c;而API接口提供访问这些数据的途径&#xff0c;使得其他软件、应用、网站等可以利用这些数据提供更丰富的功…

设计模式篇---外观模式

文章目录 概念结构实例总结 概念 外观模式&#xff1a;为子系统中的一组接口提供一个统一的入口。外观模式定义了一个高层接口&#xff0c;这个接口使得这一子系统更加容易使用。 外观模式引入了一个新的外观类&#xff0c;它为多个业务类的调用提供了一个统一的入口。主要优点…

18张值得收藏的高清卫星影像

这里分享的18张高清卫星影像&#xff0c;由吉林一号卫星拍摄。 原图来自长光卫星嘉宾在直播中分享的PPT演示文档。 18张高清卫星影像 吉林一号高分04A星&#xff0c;于2022年05月21日拍摄的北京紫禁城高清卫星影像。 北京紫禁城 云南昆明滇池国际会展中心高清卫星影像&…

jQuery【回到顶部、Swiper轮播图、立即执行函数、链式调用、参数重载、jQuery扩展】(六)-全面详解(学习总结---从入门到深化)

目录 回到顶部 Swiper轮播图 jQuery源码_立即执行函数 jQuery源码_链式调用 jQuery源码_参数重载 jQuery扩展 回到顶部 <!DOCTYPE html> <html lang"en"> <head><meta charset"UTF-8"><meta http-equiv"X-UA-Compati…

如何去阅读源码,我总结了18条心法

那么到底该如何去阅读源码呢&#xff1f;这里我总结了18条心法&#xff0c;助你修炼神功 学好JDK 身为一个Javaer&#xff0c;不论要不要阅读开源项目源码&#xff0c;都要学好JDK相关的技术。 所有的Java类开源项目&#xff0c;本质上其实就是利用JDK已有的类库和关键字实现…

这13个不经意却很不卫生的行为,很多人都没意识到

这13个不经意却很不卫生的行为&#xff0c;很多人都没意识到 北京崇文中方中医医院名医馆 2023-11-11 17:01 发表于北京 我们在生活中不经意间做出的一些动作&#xff0c;或者日常养成的一些行为习惯&#xff0c;正在悄悄伤害着我们的身体健康。可惜的是很多人都不知道这一点…

archery修改为不能自提自审核上线SQL

目录 背景修改代码效果参考 背景 我和同事都可以提交上线SQL&#xff0c;但是不能自己提交的SQL自己去审核通过。目前的情况是可以自提自审。 修改代码 找到/opt/archery/sql/utils/workflow_audit.py文件 ...省略...# 判断用户当前是否是可审核staticmethoddef can_revie…

VMware Workstation系列:Windows10 优化VMware虚拟机运行速度总结(单台、多台-ESXI)

Windows10 优化VMware虚拟机运行速度总结 一. 单台或两台同时运行前言&#xff1a;优化方法环境&#xff1a; 1、清除多余快照2、清理磁盘。3、虚拟机全局设置5、设置“优先级”6、设置“设备”7、编辑虚拟机设置8、分配合适的内存和CPU 二. 多台并行背景&#xff1a;一. 下载1…

【WiFI问题自助】解决WiFi能连上但是没有网的问题

WiFi能连上但是没有网的问题 背景&#xff1a;wifi能连上&#xff0c;但是没有网 解决 遇事不决&#xff0c;先重启啊&#xff01;怎么重启&#xff1f;拔掉电源再插上&#xff01;拔掉网线再插上&#xff01; 直接ok了。 思考记录 今天WiFi又上不了网了&#xff0c;昨天报…