diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..4772dce --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,3 @@ +{ + "cmake.sourceDirectory": "/home/robofish/RC2025/src/rm_msg" +} \ No newline at end of file diff --git a/mapping.sh b/mapping.sh index 325a87b..be6b464 100644 --- a/mapping.sh +++ b/mapping.sh @@ -2,11 +2,11 @@ source install/setup.bash commands=( "ros2 launch rm_nav_bringup bringup_real.launch.py \ - world:=RC2026 \ + world:=1 \ mode:=mapping \ lio:=fastlio \ localization:=icp \ - lio_rviz:=false \ + lio_rviz:=true \ nav_rviz:=true" ) diff --git a/nav.sh b/nav.sh index 581a73a..127fddf 100644 --- a/nav.sh +++ b/nav.sh @@ -10,7 +10,10 @@ commands=( lio_rviz:=false \ nav_rviz:=true" "ros2 launch rm_simpal_move simple_move.launch.py" - "ros2 topic pub /move_goal rm_msgs/msg/MoveGoal '{x: 0.60, y: 3.995, angle: 0.0, max_speed: 10.0, tolerance: 0.1, rotor: false}' --once" + # "ros2 topic pub /move_goal rm_msgs/msg/MoveGoal '{x: 0.61, y: 3.96, angle: 0.0, max_speed: 10.0, tolerance: 0.1, rotor: false}' --once" + # "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/pub_self.py" + # "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/receive_and_pub.py" + "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/R2_Serial.py" ) for cmd in "${commands[@]}"; do diff --git a/src/rm_driver/rm_serial_driver/script/R2_Serial.py b/src/rm_driver/rm_serial_driver/script/R2_Serial.py new file mode 100644 index 0000000..6383228 --- /dev/null +++ b/src/rm_driver/rm_serial_driver/script/R2_Serial.py @@ -0,0 +1,147 @@ +#!/usr/bin/env python3 + +import rclpy +from rclpy.node import Node +import serial +import struct +from rm_msgs.msg import DataAim +from geometry_msgs.msg import TransformStamped +import tf2_ros +import tf2_geometry_msgs + +class AimDataSerial(Node): + def __init__(self): + super().__init__('aim_data_serial') + + # 串口配置 + self.serial_port_r2 = '/dev/r2' # 原有串口,用于发送瞄准数据 + self.serial_port_r1 = '/dev/r1' # 新增串口,用于发送坐标数据 + self.baud_rate = 115200 + + # 初始化r2串口(瞄准数据) + try: + self.serial_conn_r2 = serial.Serial( + port=self.serial_port_r2, + baudrate=self.baud_rate, + timeout=1 + ) + self.get_logger().info(f'Serial port {self.serial_port_r2} opened successfully') + except Exception as e: + self.get_logger().error(f'Failed to open serial port r2: {e}') + self.serial_conn_r2 = None + + # 初始化r1串口(坐标数据) + try: + self.serial_conn_r1 = serial.Serial( + port=self.serial_port_r1, + baudrate=self.baud_rate, + timeout=1 + ) + self.get_logger().info(f'Serial port {self.serial_port_r1} opened successfully') + except Exception as e: + self.get_logger().error(f'Failed to open serial port r1: {e}') + self.serial_conn_r1 = None + + # TF2监听器,用于获取baselink在map上的坐标 + self.tf_buffer = tf2_ros.Buffer() + self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, self) + + # 订阅话题 + self.subscription = self.create_subscription( + DataAim, + '/chassis/data_aim', + self.aim_callback, + 10 + ) + + # 定时器,定期获取和发送坐标数据 + self.timer = self.create_timer(0.1, self.position_timer_callback) # 10Hz + + self.get_logger().info('Aim data serial node started') + + def aim_callback(self, msg): + if not self.serial_conn_r2: + return + + try: + # 提取yaw和distance数据 + yaw = msg.yaw + distance = msg.distance + + self.get_logger().info(f'Received - yaw: {yaw}, distance: {distance}') + + # 构建发送数据包 + # 格式: 包头(0xFF) + yaw(4字节float) + distance(4字节float) + 包尾(0xFE) + packet = bytearray() + packet.append(0xFF) # 包头 + packet.extend(struct.pack('= 22: # 最小包长度:包头(1) + 数据(16) + 校验(1) + 包尾(1) = 19 + while len(buffer) >= 18: # 包头(1) + 4个float(16) + 包尾(1) = 18字节 # 查找包头 start_idx = buffer.find(0xFF) if start_idx == -1: @@ -86,18 +85,13 @@ class ReceiveAndPubNode(Node): buffer = buffer[start_idx:] # 检查包长度 - if len(buffer) < 22: + if len(buffer) < 18: break # 查找包尾 - if buffer[21] == 0xFE: - # 校验数据 - checksum = 0 - for i in range(1, 20): - checksum ^= buffer[i] - - if checksum == buffer[20]: - # 解析数据 + if buffer[17] == 0xFE: + # 解析数据 + try: x = struct.unpack('