diff --git a/nav.sh b/nav.sh index 127fddf..4ab0e27 100644 --- a/nav.sh +++ b/nav.sh @@ -1,7 +1,7 @@ +# 备场代码 source install/setup.bash commands=( - "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/pub_aim.py" "ros2 launch rm_nav_bringup bringup_real.launch.py \ world:=RC2026 \ mode:=nav \ @@ -10,10 +10,9 @@ 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.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" + "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/slect.py map" + ) for cmd in "${commands[@]}"; do diff --git a/r1.sh b/nav1.sh similarity index 60% rename from r1.sh rename to nav1.sh index 08c20a1..2bd46f4 100644 --- a/r1.sh +++ b/nav1.sh @@ -1,16 +1,18 @@ +# 备场代码 source install/setup.bash commands=( - "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/pub_aim.py" "ros2 launch rm_nav_bringup bringup_real.launch.py \ - world:=RC2025 \ + world:=map1 \ mode:=nav \ lio:=fastlio \ localization:=icp \ 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.56, y: 3.960, 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/R2_Serial.py" + "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/slect.py map1" + ) for cmd in "${commands[@]}"; do diff --git a/nav2.sh b/nav2.sh new file mode 100644 index 0000000..a63364d --- /dev/null +++ b/nav2.sh @@ -0,0 +1,21 @@ +# 备场代码 +source install/setup.bash + +commands=( + "ros2 launch rm_nav_bringup bringup_real.launch.py \ + world:=map2 \ + mode:=nav \ + lio:=fastlio \ + localization:=icp \ + lio_rviz:=false \ + nav_rviz:=true" + "ros2 launch rm_simpal_move simple_move.launch.py" + "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/R2_Serial.py" + "/bin/python3 /home/robofish/RC2025/src/rm_driver/rm_serial_driver/script/slect.py map2" + +) + +for cmd in "${commands[@]}"; do + gnome-terminal -- bash -c "source install/setup.bash; $cmd; exec bash" + sleep 0.5 +done \ No newline at end of file diff --git a/src/rm_driver/livox_ros_driver2/src/config/MID360_config.json b/src/rm_driver/livox_ros_driver2/src/config/MID360_config.json index 4b93436..ce1158c 100644 --- a/src/rm_driver/livox_ros_driver2/src/config/MID360_config.json +++ b/src/rm_driver/livox_ros_driver2/src/config/MID360_config.json @@ -25,7 +25,7 @@ }, "lidar_configs" : [ { - "ip" : "192.168.1.137", + "ip" : "192.168.1.176", "pcl_data_type" : 1, "pattern_mode" : 0, "extrinsic_parameter" : { diff --git a/src/rm_driver/rm_serial_driver/script/R2_Serial.py b/src/rm_driver/rm_serial_driver/script/R2_Serial.py index 6383228..c9069d1 100644 --- a/src/rm_driver/rm_serial_driver/script/R2_Serial.py +++ b/src/rm_driver/rm_serial_driver/script/R2_Serial.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python3 - import rclpy from rclpy.node import Node import serial @@ -8,44 +6,29 @@ from rm_msgs.msg import DataAim from geometry_msgs.msg import TransformStamped import tf2_ros import tf2_geometry_msgs +import time class AimDataSerial(Node): def __init__(self): super().__init__('aim_data_serial') # 串口配置 - self.serial_port_r2 = '/dev/r2' # 原有串口,用于发送瞄准数据 - self.serial_port_r1 = '/dev/r1' # 新增串口,用于发送坐标数据 + self.serial_port_r2 = '/dev/r2' + self.serial_port_r1 = '/dev/ttyACM0' 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 + # 重连计数器 + self.r1_reconnect_count = 0 + self.r2_reconnect_count = 0 + self.max_reconnect_attempts = 5 - # 初始化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 + # 初始化串口连接 + self.init_serial_connections() # 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, @@ -57,8 +40,82 @@ class AimDataSerial(Node): # 定时器,定期获取和发送坐标数据 self.timer = self.create_timer(0.1, self.position_timer_callback) # 10Hz + # 计数器,用于减少日志输出 + self.position_counter = 0 + self.get_logger().info('Aim data serial node started') + def init_serial_connections(self): + """初始化串口连接""" + # 初始化r2串口(瞄准数据) + self.serial_conn_r2 = self.open_serial_port(self.serial_port_r2, "r2") + + # 初始化r1串口(坐标数据) + self.serial_conn_r1 = self.open_serial_port(self.serial_port_r1, "r1") + + def open_serial_port(self, port, name): + """打开串口,返回串口对象或None""" + try: + ser = serial.Serial( + port=port, + baudrate=self.baud_rate, + timeout=1 + ) + self.get_logger().info(f'Serial port {port} ({name}) opened successfully') + return ser + except Exception as e: + self.get_logger().error(f'Failed to open serial port {name}: {e}') + return None + + def reconnect_serial(self, port, name, current_conn, reconnect_count_attr): + """尝试重新连接串口""" + reconnect_count = getattr(self, reconnect_count_attr) + if reconnect_count >= self.max_reconnect_attempts: + return None + + self.get_logger().warn(f'Attempting to reconnect {name} (attempt {reconnect_count + 1})') + + # 关闭现有连接 + if current_conn and current_conn.is_open: + current_conn.close() + + # 等待一下再重连 + time.sleep(0.5) + + # 尝试重新连接 + new_conn = self.open_serial_port(port, name) + setattr(self, reconnect_count_attr, reconnect_count + 1) + + if new_conn: + # 重连成功,重置计数器 + setattr(self, reconnect_count_attr, 0) + self.get_logger().info(f'{name} reconnected successfully') + + return new_conn + + def safe_serial_write(self, serial_conn, data, port_name): + """安全的串口写入,包含错误处理和重连""" + if not serial_conn: + return False + + try: + serial_conn.write(data) + return True + except Exception as e: + self.get_logger().error(f'Write error on {port_name}: {e}') + + # 尝试重连 + if port_name == "r1": + self.serial_conn_r1 = self.reconnect_serial( + self.serial_port_r1, "r1", self.serial_conn_r1, "r1_reconnect_count" + ) + elif port_name == "r2": + self.serial_conn_r2 = self.reconnect_serial( + self.serial_port_r2, "r2", self.serial_conn_r2, "r2_reconnect_count" + ) + + return False + def aim_callback(self, msg): if not self.serial_conn_r2: return @@ -79,8 +136,8 @@ class AimDataSerial(Node): packet.append(0xFE) # 包尾 # 发送数据到r2串口 - self.serial_conn_r2.write(packet) - self.get_logger().info(f'Sent aim packet to r2: {packet.hex()}') + if self.safe_serial_write(self.serial_conn_r2, packet, "r2"): + self.get_logger().info(f'Sent aim packet to r2: {packet.hex()}') except Exception as e: self.get_logger().error(f'Error in aim_callback: {e}') @@ -102,7 +159,10 @@ class AimDataSerial(Node): y = transform.transform.translation.y z = transform.transform.translation.z - self.get_logger().info(f'Position - x: {x:.3f}, y: {y:.3f}, z: {z:.3f}') + # 减少日志输出频率 + self.position_counter += 1 + if self.position_counter % 50 == 0: # 每5秒打印一次 + self.get_logger().info(f'Position - x: {x:.3f}, y: {y:.3f}, z: {z:.3f}') # 构建坐标数据包 # 格式: 包头(0xAA) + x(4字节float) + y(4字节float) + z(4字节float) + 包尾(0xBB) @@ -114,12 +174,14 @@ class AimDataSerial(Node): packet.append(0xBB) # 包尾 # 发送数据到r1串口 - self.serial_conn_r1.write(packet) - self.get_logger().info(f'Sent position packet to r1: {packet.hex()}') + if self.safe_serial_write(self.serial_conn_r1, packet, "r1"): + if self.position_counter % 50 == 0: # 只在打印位置时也打印发送信息 + self.get_logger().info(f'Sent position packet to r1: {packet.hex()}') except tf2_ros.TransformException as e: # TF变换异常,可能是坐标系不存在或时间不同步 - self.get_logger().warn(f'Transform exception: {e}') + if self.position_counter % 100 == 0: # 减少TF异常日志频率 + self.get_logger().warn(f'Transform exception: {e}') except Exception as e: self.get_logger().error(f'Error in position_timer_callback: {e}') diff --git a/src/rm_driver/rm_serial_driver/script/pub_OnlyAim.py b/src/rm_driver/rm_serial_driver/script/pub_OnlyAim.py deleted file mode 100644 index af70745..0000000 --- a/src/rm_driver/rm_serial_driver/script/pub_OnlyAim.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python3 - -import rclpy -from rclpy.node import Node -import serial -import struct -from rm_msgs.msg import DataAim # 假设使用DataAim消息类型,您可以根据实际消息类型调整 -class AimDataSerial(Node): - def __init__(self): - super().__init__('aim_data_serial') - - # 串口配置 - self.serial_port = '/dev/ttyUSB0' # 根据实际串口设备调整 - self.baud_rate = 115200 - - try: - self.serial_conn = serial.Serial( - port=self.serial_port, - baudrate=self.baud_rate, - timeout=1 - ) - self.get_logger().info(f'Serial port {self.serial_port} opened successfully') - except Exception as e: - self.get_logger().error(f'Failed to open serial port: {e}') - return - - # 订阅话题 - self.subscription = self.create_subscription( - DataAim, # 根据实际消息类型调整 - '/chassis/data_aim', - self.aim_callback, - 10 - ) - - self.get_logger().info('Aim data serial node started') - - def aim_callback(self, msg): - try: - # 提取yaw和distance数据 - # 根据实际消息结构调整,这里假设使用Point32的x和y字段 - 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(' 0: - data = self.receive_serial.read(self.receive_serial.in_waiting) - buffer.extend(data) - - # 查找完整的数据包 - while len(buffer) >= 18: # 包头(1) + 4个float(16) + 包尾(1) = 18字节 - # 查找包头 - start_idx = buffer.find(0xFF) - if start_idx == -1: - break - - # 移除包头前的数据 - if start_idx > 0: - buffer = buffer[start_idx:] - - # 检查包长度 - if len(buffer) < 18: - break - - # 查找包尾 - if buffer[17] == 0xFE: - # 解析数据 - try: - x = struct.unpack('