diff --git a/test_dummy2_integration.py b/test_dummy2_integration.py new file mode 100644 index 0000000..d2f63c3 --- /dev/null +++ b/test_dummy2_integration.py @@ -0,0 +1,254 @@ +#!/usr/bin/env python3 +""" +Dummy2 机械臂接入 UniLab 系统测试脚本 +""" + +import os +import sys +import time +import yaml +import json + +def test_device_model_files(): + """测试设备模型文件是否完整""" + print("=== 测试设备模型文件 ===") + + device_path = "/Users/dp/Documents/Uni-Lab-OS/unilabos/device_mesh/devices/dummy2_robot" + + required_files = [ + "macro_device.xacro", + "dummy2_robot.json", + "config/joint_limits.yaml", + "config/default_kinematics.yaml", + "config/physical_parameters.yaml", + "config/visual_parameters.yaml" + ] + + required_meshes = [ + "meshes/base_link.stl", + "meshes/J1_1.stl", + "meshes/J2_1.stl", + "meshes/J3_1.stl", + "meshes/J4_1.stl", + "meshes/J5_1.stl", + "meshes/J6_1.stl", + "meshes/camera_1.stl" + ] + + all_files = required_files + required_meshes + missing_files = [] + + for file_path in all_files: + full_path = os.path.join(device_path, file_path) + if not os.path.exists(full_path): + missing_files.append(file_path) + else: + print(f"✅ {file_path}") + + if missing_files: + print(f"❌ 缺少文件: {missing_files}") + return False + else: + print("✅ 所有模型文件都存在") + return True + +def test_driver_file(): + """测试驱动文件""" + print("\n=== 测试驱动文件 ===") + + driver_path = "/Users/dp/Documents/Uni-Lab-OS/unilabos/devices/ros_dev/moveit_interface.py" + + if not os.path.exists(driver_path): + print(f"❌ 驱动文件不存在: {driver_path}") + return False + + try: + # 尝试导入驱动类 + sys.path.insert(0, os.path.dirname(driver_path)) + from unilabos.devices.ros_dev.moveit_interface import MoveitInterface + print("✅ 驱动文件存在且可导入") + + # 检查必要的方法 + required_methods = [ + '__init__', + 'post_init', + 'check_tf_update_actions', + 'resource_manager', + 'wait_for_resource_action', + 'moveit_joint_task', + 'moveit_task' + ] + + missing_methods = [] + for method in required_methods: + if not hasattr(MoveitInterface, method): + missing_methods.append(method) + + if missing_methods: + print(f"❌ 驱动类缺少方法: {missing_methods}") + return False + else: + print("✅ 驱动类包含所有必要方法") + return True + + except ImportError as e: + print(f"❌ 驱动文件导入失败: {e}") + return False + +def test_registry_config(): + """测试注册表配置""" + print("\n=== 测试注册表配置 ===") + + registry_path = "/Users/dp/Documents/Uni-Lab-OS/unilabos/registry/devices/robot_arm.yaml" + + if not os.path.exists(registry_path): + print(f"❌ 注册表文件不存在: {registry_path}") + return False + + try: + with open(registry_path, 'r', encoding='utf-8') as f: + config = yaml.safe_load(f) + + if 'robotic_arm.Dummy2' not in config: + print("❌ 注册表中没有找到 robotic_arm.Dummy2 配置") + return False + + dummy2_config = config['robotic_arm.Dummy2'] + + # 检查必要的配置项 + required_keys = [ + 'category', + 'class', + 'description', + 'init_param_schema', + 'model', + 'version' + ] + + missing_keys = [] + for key in required_keys: + if key not in dummy2_config: + missing_keys.append(key) + + if missing_keys: + print(f"❌ Dummy2配置缺少字段: {missing_keys}") + return False + + # 检查模块路径 + module_path = dummy2_config.get('class', {}).get('module') + if module_path != 'unilabos.devices.ros_dev.moveit_interface:MoveitInterface': + print(f"❌ 模块路径不正确: {module_path}") + return False + + # 检查动作定义 + actions = dummy2_config.get('class', {}).get('action_value_mappings', {}) + required_actions = [ + 'auto-check_tf_update_actions', + 'auto-post_init', + 'auto-resource_manager', + 'auto-wait_for_resource_action', + 'auto-moveit_joint_task', + 'auto-moveit_task', + 'pick_and_place' + ] + + missing_actions = [] + for action in required_actions: + if action not in actions: + missing_actions.append(action) + + if missing_actions: + print(f"❌ 缺少动作定义: {missing_actions}") + return False + + print("✅ 注册表配置完整且正确") + return True + + except Exception as e: + print(f"❌ 注册表配置检查失败: {e}") + return False + +def test_can2eth_connectivity(): + """测试CAN2ETH连接(可选)""" + print("\n=== 测试CAN2ETH连接 ===") + + try: + import socket + import struct + + # 尝试连接CAN2ETH网关 + sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + sock.settimeout(2.0) + + can2eth_host = "192.168.8.88" + can2eth_port = 8080 + + # 发送ping命令 + ping_cmd = struct.pack('>B', 0xFF) + sock.sendto(ping_cmd, (can2eth_host, can2eth_port)) + + try: + data, addr = sock.recvfrom(1024) + if len(data) > 0: + print(f"✅ CAN2ETH网关 {can2eth_host}:{can2eth_port} 连接成功") + return True + except socket.timeout: + print(f"⚠️ CAN2ETH网关 {can2eth_host}:{can2eth_port} 无响应(可能未启动)") + return False + + except Exception as e: + print(f"⚠️ CAN2ETH连接测试失败: {e}") + return False + finally: + if 'sock' in locals(): + sock.close() + +def main(): + """主测试函数""" + print("🤖 Dummy2 机械臂接入 UniLab 系统测试") + print("=" * 50) + + tests = [ + ("设备模型文件", test_device_model_files), + ("驱动文件", test_driver_file), + ("注册表配置", test_registry_config), + ("CAN2ETH连接", test_can2eth_connectivity) + ] + + results = [] + + for test_name, test_func in tests: + try: + result = test_func() + results.append((test_name, result)) + except Exception as e: + print(f"❌ {test_name}测试异常: {e}") + results.append((test_name, False)) + + print("\n" + "=" * 50) + print("📊 测试结果汇总:") + + passed = 0 + total = len(results) + + for test_name, result in results: + status = "✅ 通过" if result else "❌ 失败" + print(f" {test_name}: {status}") + if result: + passed += 1 + + print(f"\n总体结果: {passed}/{total} 项测试通过") + + if passed == total: + print("🎉 Dummy2 机械臂已成功接入 UniLab 系统!") + print("\n📋 后续步骤:") + print("1. 启动 CAN2ETH 服务: ros2 launch dummy2_can2eth dummy2_can2eth_server.launch.py") + print("2. 在 UniLab 界面中添加 Dummy2 设备实例") + print("3. 测试设备初始化和基本功能") + else: + print("⚠️ 还有一些问题需要解决才能完全接入") + + return passed == total + +if __name__ == "__main__": + main() diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/default_kinematics.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/default_kinematics.yaml new file mode 100644 index 0000000..a7c5ae6 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/default_kinematics.yaml @@ -0,0 +1,25 @@ +dummy2_robot: + kinematics: + # DH parameters for Dummy2 6-DOF robot arm + # [theta, d, a, alpha] for each joint + joint_1: [0.0, 0.1, 0.0, 1.5708] # Base rotation + joint_2: [0.0, 0.0, 0.2, 0.0] # Shoulder + joint_3: [0.0, 0.0, 0.15, 0.0] # Elbow + joint_4: [0.0, 0.1, 0.0, 1.5708] # Wrist roll + joint_5: [0.0, 0.0, 0.0, -1.5708] # Wrist pitch + joint_6: [0.0, 0.06, 0.0, 0.0] # Wrist yaw + + # Tool center point offset from last joint + tcp_offset: + x: 0.0 + y: 0.0 + z: 0.04 + + # Workspace limits + workspace: + x_min: -0.5 + x_max: 0.5 + y_min: -0.5 + y_max: 0.5 + z_min: 0.0 + z_max: 0.6 diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.srdf b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.srdf new file mode 100644 index 0000000..5b53b86 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.srdf @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.urdf.xacro b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.urdf.xacro new file mode 100644 index 0000000..1fb0c97 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.xacro b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.xacro new file mode 100644 index 0000000..f7959cb --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2.xacro @@ -0,0 +1,237 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/dummy2_simulated_config.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2_simulated_config.yaml new file mode 100644 index 0000000..4856bf1 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/dummy2_simulated_config.yaml @@ -0,0 +1,73 @@ +############################################### +# Modify all parameters related to servoing here +############################################### +# adapt to dummy2 by Muzhxiaowen, check out the details on bilibili.com + +use_gazebo: false # Whether the robot is started in a Gazebo simulation environment + +## Properties of incoming commands +command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s +scale: + # Scale parameters are only used if command_in_type=="unitless" + linear: 0.4 # Max linear velocity. Unit is [m/s]. Only used for Cartesian commands. + rotational: 0.8 # Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands. + # Max joint angular/linear velocity. Only used for joint commands on joint_command_in_topic. + joint: 0.5 + +# Optionally override Servo's internal velocity scaling when near singularity or collision (0.0 = use internal velocity scaling) +# override_velocity_scaling_factor = 0.0 # valid range [0.0:1.0] + +## Properties of outgoing commands +publish_period: 0.034 # 1/Nominal publish rate [seconds] +low_latency_mode: false # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored) + +# What type of topic does your robot driver expect? +# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory +command_out_type: trajectory_msgs/JointTrajectory + +# What to publish? Can save some bandwidth as most robots only require positions or velocities +publish_joint_positions: true +publish_joint_velocities: true +publish_joint_accelerations: false + +## Plugins for smoothing outgoing commands +smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin" + +# If is_primary_planning_scene_monitor is set to true, the Servo server's PlanningScene advertises the /get_planning_scene service, +# which other nodes can use as a source for information about the planning environment. +# NOTE: If a different node in your system is responsible for the "primary" planning scene instance (e.g. the MoveGroup node), +# then is_primary_planning_scene_monitor needs to be set to false. +is_primary_planning_scene_monitor: true + +## MoveIt properties +move_group_name: dummy2_arm # Often 'manipulator' or 'arm' +planning_frame: base_link # The MoveIt planning frame. Often 'base_link' or 'world' + +## Other frames +ee_frame_name: J6_1 # The name of the end effector link, used to return the EE pose +robot_link_command_frame: base_link # commands must be given in the frame of a robot link. Usually either the base or end effector + +## Stopping behaviour +incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command +# If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish. +# Important because ROS may drop some messages and we need the robot to halt reliably. +num_outgoing_halt_msgs_to_publish: 4 + +## Configure handling of singularities and joint limits +lower_singularity_threshold: 170.0 # Start decelerating when the condition number hits this (close to singularity) +hard_stop_singularity_threshold: 3000.0 # Stop when the condition number hits this +joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. +leaving_singularity_threshold_multiplier: 2.0 # Multiply the hard stop limit by this when leaving singularity (see https://github.com/ros-planning/moveit2/pull/620) + +## Topic names +cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands +joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands +joint_topic: /joint_states +status_topic: ~/status # Publish status to this topic +command_out_topic: /dummy2_arm_controller/joint_trajectory # Publish outgoing commands here + +## Collision checking for the entire robot body +check_collisions: true # Check collisions? +collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. +self_collision_proximity_threshold: 0.001 # Start decelerating when a self-collision is this far [m] +scene_collision_proximity_threshold: 0.002 # Start decelerating when a scene collision is this far [m] diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/initial_positions.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/initial_positions.yaml new file mode 100644 index 0000000..841bba0 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for dummy2's ros2_control fake system + +initial_positions: + Joint1: 0 + Joint2: 0 + Joint3: 0 + Joint4: 0 + Joint5: 0 + Joint6: 0 \ No newline at end of file diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/joint_limits.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/joint_limits.yaml new file mode 100644 index 0000000..151fb30 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint_1: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: false + max_acceleration: 0 + joint_2: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: false + max_acceleration: 0 + joint_3: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: false + max_acceleration: 0 + joint_4: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: false + max_acceleration: 0 + joint_5: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: false + max_acceleration: 0 + joint_6: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/kinematics.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/kinematics.yaml new file mode 100644 index 0000000..55cefc6 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/kinematics.yaml @@ -0,0 +1,4 @@ +dummy2_arm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.5 \ No newline at end of file diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/macro.ros2_control.xacro b/unilabos/device_mesh/devices/dummy2_robot/config/macro.ros2_control.xacro new file mode 100644 index 0000000..58b38a5 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/macro.ros2_control.xacro @@ -0,0 +1,57 @@ + + + + + + + + + + dummy2_hardware/Dummy2Hardware + + + + + ${initial_positions['Joint1']} + + + + + + + ${initial_positions['Joint2']} + + + + + + + ${initial_positions['Joint3']} + + + + + + + ${initial_positions['Joint4']} + + + + + + + ${initial_positions['Joint5']} + + + + + + + ${initial_positions['Joint6']} + + + + + + + diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/move_group.json b/unilabos/device_mesh/devices/dummy2_robot/config/move_group.json new file mode 100644 index 0000000..2ff1d67 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/move_group.json @@ -0,0 +1,14 @@ +{ + "arm": { + "joint_names": [ + "joint_1", + "joint_2", + "joint_3", + "joint_4", + "joint_5", + "joint_6" + ], + "base_link_name": "base_link", + "end_effector_name": "tool_link" + } +} \ No newline at end of file diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/moveit.rviz b/unilabos/device_mesh/devices/dummy2_robot/config/moveit.rviz new file mode 100644 index 0000000..99bb740 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/moveit_controllers.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/moveit_controllers.yaml new file mode 100644 index 0000000..153ff5e --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/moveit_controllers.yaml @@ -0,0 +1,21 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - dummy2_arm_controller + + dummy2_arm_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - Joint1 + - Joint2 + - Joint3 + - Joint4 + - Joint5 + - Joint6 + action_ns: follow_joint_trajectory + default: true \ No newline at end of file diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/physical_parameters.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/physical_parameters.yaml new file mode 100644 index 0000000..cd6f60c --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/physical_parameters.yaml @@ -0,0 +1,39 @@ +dummy2_robot: + # Physical properties for each link + link_masses: + base_link: 5.0 + link_1: 3.0 + link_2: 2.5 + link_3: 2.0 + link_4: 1.5 + link_5: 1.0 + link_6: 0.5 + + # Center of mass for each link (relative to joint frame) + link_com: + base_link: [0.0, 0.0, 0.05] + link_1: [0.0, 0.0, 0.05] + link_2: [0.1, 0.0, 0.0] + link_3: [0.08, 0.0, 0.0] + link_4: [0.0, 0.0, 0.05] + link_5: [0.0, 0.0, 0.03] + link_6: [0.0, 0.0, 0.02] + + # Moment of inertia matrices + link_inertias: + base_link: [0.02, 0.0, 0.0, 0.02, 0.0, 0.02] + link_1: [0.01, 0.0, 0.0, 0.01, 0.0, 0.01] + link_2: [0.008, 0.0, 0.0, 0.008, 0.0, 0.008] + link_3: [0.006, 0.0, 0.0, 0.006, 0.0, 0.006] + link_4: [0.004, 0.0, 0.0, 0.004, 0.0, 0.004] + link_5: [0.002, 0.0, 0.0, 0.002, 0.0, 0.002] + link_6: [0.001, 0.0, 0.0, 0.001, 0.0, 0.001] + + # Motor specifications + motor_specs: + joint_1: { max_torque: 150.0, max_speed: 2.0, gear_ratio: 100 } + joint_2: { max_torque: 150.0, max_speed: 2.0, gear_ratio: 100 } + joint_3: { max_torque: 150.0, max_speed: 2.0, gear_ratio: 100 } + joint_4: { max_torque: 50.0, max_speed: 2.0, gear_ratio: 50 } + joint_5: { max_torque: 50.0, max_speed: 2.0, gear_ratio: 50 } + joint_6: { max_torque: 25.0, max_speed: 2.0, gear_ratio: 25 } diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/pilz_cartesian_limits.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..b2997ca --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/ros2_controllers.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/ros2_controllers.yaml new file mode 100644 index 0000000..6265fa4 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + dummy2_arm_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +dummy2_arm_controller: + ros__parameters: + joints: + - Joint1 + - Joint2 + - Joint3 + - Joint4 + - Joint5 + - Joint6 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/unilabos/device_mesh/devices/dummy2_robot/config/visual_parameters.yaml b/unilabos/device_mesh/devices/dummy2_robot/config/visual_parameters.yaml new file mode 100644 index 0000000..e9cc661 --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/config/visual_parameters.yaml @@ -0,0 +1,35 @@ +dummy2_robot: + # Visual appearance settings + materials: + base_material: + color: [0.8, 0.8, 0.8, 1.0] # Light gray + metallic: 0.1 + roughness: 0.3 + + link_material: + color: [0.2, 0.2, 0.8, 1.0] # Blue + metallic: 0.3 + roughness: 0.2 + + joint_material: + color: [0.6, 0.6, 0.6, 1.0] # Dark gray + metallic: 0.5 + roughness: 0.1 + + camera_material: + color: [0.1, 0.1, 0.1, 1.0] # Black + metallic: 0.0 + roughness: 0.8 + + # Mesh scaling factors + mesh_scale: [0.001, 0.001, 0.001] # Convert mm to m + + # Collision geometry simplification + collision_geometries: + base_link: "cylinder" # radius: 0.08, height: 0.1 + link_1: "cylinder" # radius: 0.05, height: 0.15 + link_2: "box" # size: [0.2, 0.08, 0.08] + link_3: "box" # size: [0.15, 0.06, 0.06] + link_4: "cylinder" # radius: 0.03, height: 0.1 + link_5: "cylinder" # radius: 0.025, height: 0.06 + link_6: "cylinder" # radius: 0.02, height: 0.04 diff --git a/unilabos/device_mesh/devices/dummy2_robot/joint_limit.yaml b/unilabos/device_mesh/devices/dummy2_robot/joint_limit.yaml new file mode 100644 index 0000000..4bbb56c --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/joint_limit.yaml @@ -0,0 +1,37 @@ +joint_limits: + + joint_1: + effort: 150 + velocity: 2.0 + lower: !degrees -180 + upper: !degrees 180 + + joint_2: + effort: 150 + velocity: 2.0 + lower: !degrees -90 + upper: !degrees 90 + + joint_3: + effort: 150 + velocity: 2.0 + lower: !degrees -90 + upper: !degrees 90 + + joint_4: + effort: 50 + velocity: 2.0 + lower: !degrees -180 + upper: !degrees 180 + + joint_5: + effort: 50 + velocity: 2.0 + lower: !degrees -90 + upper: !degrees 90 + + joint_6: + effort: 25 + velocity: 2.0 + lower: !degrees -180 + upper: !degrees 180 diff --git a/unilabos/device_mesh/devices/dummy2_robot/macro_device.xacro b/unilabos/device_mesh/devices/dummy2_robot/macro_device.xacro new file mode 100644 index 0000000..d4ad1fd --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/macro_device.xacro @@ -0,0 +1,314 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + dummy2_hardware_interface/Dummy2HardwareInterface + $(arg can2eth_ip) + $(arg can2eth_port) + + + + + ${limit_joint_1['lower']} + ${limit_joint_1['upper']} + + + + + + + + ${limit_joint_2['lower']} + ${limit_joint_2['upper']} + + + + + + + + ${limit_joint_3['lower']} + ${limit_joint_3['upper']} + + + + + + + + ${limit_joint_4['lower']} + ${limit_joint_4['upper']} + + + + + + + + ${limit_joint_5['lower']} + ${limit_joint_5['upper']} + + + + + + + + ${limit_joint_6['lower']} + ${limit_joint_6['upper']} + + + + + + + + + diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/J1_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/J1_1.stl new file mode 100644 index 0000000..744ff33 Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/J1_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/J2_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/J2_1.stl new file mode 100644 index 0000000..94b75fe Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/J2_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/J3_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/J3_1.stl new file mode 100644 index 0000000..fb172d8 Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/J3_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/J4_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/J4_1.stl new file mode 100644 index 0000000..a7e12a6 Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/J4_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/J5_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/J5_1.stl new file mode 100644 index 0000000..091eccc Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/J5_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/J6_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/J6_1.stl new file mode 100644 index 0000000..55f51b2 Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/J6_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/base_link.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/base_link.stl new file mode 100644 index 0000000..f5ded8a Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/base_link.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/camera_1.stl b/unilabos/device_mesh/devices/dummy2_robot/meshes/camera_1.stl new file mode 100644 index 0000000..b5a6ece Binary files /dev/null and b/unilabos/device_mesh/devices/dummy2_robot/meshes/camera_1.stl differ diff --git a/unilabos/device_mesh/devices/dummy2_robot/meshes/dummy2.xacro b/unilabos/device_mesh/devices/dummy2_robot/meshes/dummy2.xacro new file mode 100644 index 0000000..f7959cb --- /dev/null +++ b/unilabos/device_mesh/devices/dummy2_robot/meshes/dummy2.xacro @@ -0,0 +1,237 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/unilabos/registry/devices/robot_arm.yaml b/unilabos/registry/devices/robot_arm.yaml index 61803d1..8bf9fd6 100644 --- a/unilabos/registry/devices/robot_arm.yaml +++ b/unilabos/registry/devices/robot_arm.yaml @@ -1,3 +1,318 @@ +robotic_arm.Dummy2: + category: + - robot_arm + class: + action_value_mappings: + auto-check_tf_update_actions: + feedback: {} + goal: {} + goal_default: {} + handles: [] + result: {} + schema: + description: check_tf_update_actions的参数schema + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: check_tf_update_actions参数 + type: object + type: UniLabJsonCommand + auto-moveit_joint_task: + feedback: {} + goal: {} + goal_default: + joint_names: null + joint_positions: null + move_group: null + retry: 10 + speed: 1 + handles: [] + result: {} + schema: + description: moveit_joint_task的参数schema(关节空间规划) + properties: + feedback: {} + goal: + properties: + joint_names: + type: string + joint_positions: + type: string + move_group: + type: string + retry: + default: 10 + type: string + speed: + default: 1 + type: string + required: + - move_group + - joint_positions + type: object + result: {} + required: + - goal + title: moveit_joint_task参数 + type: object + type: UniLabJsonCommand + auto-moveit_task: + feedback: {} + goal: {} + goal_default: + cartesian: false + move_group: null + offsets: + - 0 + - 0 + - 0 + position: null + quaternion: null + retry: 10 + speed: 1 + target_link: null + handles: [] + result: {} + schema: + description: moveit_task的参数schema(笛卡尔空间/位姿规划) + properties: + feedback: {} + goal: + properties: + cartesian: + default: false + type: string + move_group: + type: string + offsets: + default: + - 0 + - 0 + - 0 + type: string + position: + type: string + quaternion: + type: string + retry: + default: 10 + type: string + speed: + default: 1 + type: string + target_link: + type: string + required: + - move_group + - position + - quaternion + type: object + result: {} + required: + - goal + title: moveit_task参数 + type: object + type: UniLabJsonCommand + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: [] + result: {} + schema: + description: post_init的参数schema + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-resource_manager: + feedback: {} + goal: {} + goal_default: + parent_link: null + resource: null + handles: [] + result: {} + schema: + description: resource_manager的参数schema + properties: + feedback: {} + goal: + properties: + parent_link: + type: string + resource: + type: string + required: + - resource + - parent_link + type: object + result: {} + required: + - goal + title: resource_manager参数 + type: object + type: UniLabJsonCommand + auto-set_position: + feedback: {} + goal: {} + goal_default: + command: null + handles: [] + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + command: + type: string + required: + - command + type: object + result: {} + required: + - goal + title: set_position参数 + type: object + type: UniLabJsonCommand + auto-set_status: + feedback: {} + goal: {} + goal_default: + command: null + handles: [] + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + command: + type: string + required: + - command + type: object + result: {} + required: + - goal + title: set_status参数 + type: object + type: UniLabJsonCommand + auto-wait_for_resource_action: + feedback: {} + goal: {} + goal_default: {} + handles: [] + result: {} + schema: + description: wait_for_resource_action的参数schema + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: wait_for_resource_action参数 + type: object + type: UniLabJsonCommand + pick_and_place: + feedback: {} + goal: + command: command + goal_default: + command: '' + handles: [] + result: {} + schema: + description: '' + properties: + feedback: + properties: + status: + type: string + required: + - status + title: SendCmd_Feedback + type: object + goal: + properties: + command: + type: string + required: + - command + title: SendCmd_Goal + type: object + result: + properties: + return_info: + type: string + success: + type: boolean + required: + - return_info + - success + title: SendCmd_Result + type: object + required: + - goal + title: SendCmd + type: object + type: SendCmd + module: unilabos.devices.ros_dev.moveit_interface:MoveitInterface + status_types: {} + type: python + config_info: [] + description: Dummy2 六自由度机械臂(与线性滑台可选配)使用 MoveIt2 进行运动规划与控制。 通过 ROS2 Action 与 MoveItInterface + 对接,支持关节空间与笛卡尔空间规划、 轨迹执行、碰撞检测与逆运动学。底层 CAN2ETH 通信由独立服务提供,本设备 不直接管理网络参数。 + handles: [] + icon: dummy2_robot + init_param_schema: + config: + properties: + device_config: + type: string + joint_poses: + type: string + moveit_type: + type: string + rotation: + type: string + required: + - moveit_type + - joint_poses + type: object + data: + properties: {} + required: [] + type: object + model: + mesh: dummy2_robot + type: device + version: 1.0.0 robotic_arm.SCARA_with_slider.virtual: category: - robot_arm