mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 13:01:12 +00:00
3d sim (#97)
* 修改lh的json启动 * 修改lh的json启动 * 修改backend,做成sim的通用backend * 修改yaml的地址,3D模型适配网页生产环境 * 添加laiyu硬件连接 * 修改移液枪的状态判断方法, 修改移液枪的状态判断方法, 添加三轴的表定点与零点之间的转换 添加三轴真实移动的backend * 修改laiyu移液站 简化移动方法, 取消软件限制位置, 修改当值使用Z轴时也需要重新复位Z轴的问题 * 更新lh以及laiyu workshop 1,现在可以直接通过修改backend,适配其他的移液站,主类依旧使用LiquidHandler,不用重新编写 2,修改枪头判断标准,使用枪头自身判断而不是类的判断, 3,将归零参数用毫米计算,方便手动调整, 4,修改归零方式,上电使用机械归零,确定机械零点,手动归零设置工作区域零点方便计算,二者互不干涉 * 修改枪头动作 * 修改虚拟仿真方法 --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: Junhan Chang <changjh@dp.tech>
This commit is contained in:
@@ -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
|
||||
45
unilabos/device_mesh/devices/dummy2_robot/config/dummy2.srdf
Normal file
45
unilabos/device_mesh/devices/dummy2_robot/config/dummy2.srdf
Normal file
@@ -0,0 +1,45 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!--This does not replace URDF, and is not an extension of URDF.
|
||||
This is a format for representing semantic information about the robot structure.
|
||||
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
|
||||
-->
|
||||
<robot name="dummy2">
|
||||
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
|
||||
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
|
||||
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
|
||||
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
|
||||
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
|
||||
<group name="dummy2_arm">
|
||||
<joint name="virtual_joint"/>
|
||||
<joint name="Joint1"/>
|
||||
<joint name="Joint2"/>
|
||||
<joint name="Joint3"/>
|
||||
<joint name="Joint4"/>
|
||||
<joint name="Joint5"/>
|
||||
<joint name="Joint6"/>
|
||||
</group>
|
||||
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
|
||||
<group_state name="home" group="dummy2_arm">
|
||||
<joint name="Joint1" value="0"/>
|
||||
<joint name="Joint2" value="0"/>
|
||||
<joint name="Joint3" value="0"/>
|
||||
<joint name="Joint4" value="0"/>
|
||||
<joint name="Joint5" value="0"/>
|
||||
<joint name="Joint6" value="0"/>
|
||||
</group_state>
|
||||
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
|
||||
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="base_link"/>
|
||||
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
|
||||
<disable_collisions link1="J1_1" link2="J2_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="J1_1" link2="J3_1" reason="Never"/>
|
||||
<disable_collisions link1="J1_1" link2="J4_1" reason="Never"/>
|
||||
<disable_collisions link1="J1_1" link2="base_link" reason="Adjacent"/>
|
||||
<disable_collisions link1="J2_1" link2="J3_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="J3_1" link2="J4_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="J3_1" link2="J5_1" reason="Never"/>
|
||||
<disable_collisions link1="J3_1" link2="J6_1" reason="Never"/>
|
||||
<disable_collisions link1="J3_1" link2="base_link" reason="Never"/>
|
||||
<disable_collisions link1="J4_1" link2="J5_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="J4_1" link2="J6_1" reason="Never"/>
|
||||
<disable_collisions link1="J5_1" link2="J6_1" reason="Adjacent"/>
|
||||
</robot>
|
||||
@@ -0,0 +1,70 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="dummy2" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<transmission name="Joint1_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="Joint1">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Joint1_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="Joint2_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="Joint2">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Joint2_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="Joint3_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="Joint3">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Joint3_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="Joint4_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="Joint4">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Joint4_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="Joint5_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="Joint5">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Joint5_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="Joint6_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="Joint6">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Joint6_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</robot>
|
||||
@@ -0,0 +1,14 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="dummy2">
|
||||
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
|
||||
|
||||
<!-- Import dummy2 urdf file -->
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/dummy2.xacro" />
|
||||
|
||||
<!-- Import control_xacro -->
|
||||
<xacro:include filename="dummy2.ros2_control.xacro" />
|
||||
|
||||
|
||||
<xacro:dummy2_ros2_control name="FakeSystem" initial_positions_file="$(arg initial_positions_file)"/>
|
||||
|
||||
</robot>
|
||||
@@ -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]
|
||||
@@ -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
|
||||
@@ -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
|
||||
@@ -0,0 +1,4 @@
|
||||
dummy2_arm:
|
||||
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
|
||||
kinematics_solver_search_resolution: 0.0050000000000000001
|
||||
kinematics_solver_timeout: 0.5
|
||||
@@ -0,0 +1,60 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:macro name="dummy2_robot_ros2_control" params="device_name mesh_path">
|
||||
<xacro:property name="initial_positions" value="${load_yaml(mesh_path + '/devices/dummy2_robot/config/initial_positions.yaml')['initial_positions']}"/>
|
||||
|
||||
<ros2_control name="${device_name}dummy2" type="system">
|
||||
<hardware>
|
||||
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
|
||||
<plugin>mock_components/GenericSystem</plugin>
|
||||
</hardware>
|
||||
|
||||
<!-- <plugin>mock_components/GenericSystem</plugin> -->
|
||||
<joint name="${device_name}Joint1">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Joint1']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="${device_name}Joint2">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Joint2']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="${device_name}Joint3">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Joint3']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="${device_name}Joint4">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Joint4']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="${device_name}Joint5">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Joint5']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="${device_name}Joint6">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Joint6']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
|
||||
|
||||
</ros2_control>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
@@ -0,0 +1,49 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:macro name="dummy2_robot_srdf" params="device_name">
|
||||
|
||||
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
|
||||
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
|
||||
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
|
||||
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
|
||||
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names
|
||||
This is a format for representing semantic information about the robot structure.
|
||||
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
|
||||
-->
|
||||
<group name="${device_name}dummy2_arm">
|
||||
<joint name="${device_name}virtual_joint"/>
|
||||
<joint name="${device_name}Joint1"/>
|
||||
<joint name="${device_name}Joint2"/>
|
||||
<joint name="${device_name}Joint3"/>
|
||||
<joint name="${device_name}Joint4"/>
|
||||
<joint name="${device_name}Joint5"/>
|
||||
<joint name="${device_name}Joint6"/>
|
||||
</group>
|
||||
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
|
||||
<group_state name="home" group="${device_name}dummy2_arm">
|
||||
<joint name="${device_name}Joint1" value="0"/>
|
||||
<joint name="${device_name}Joint2" value="0"/>
|
||||
<joint name="${device_name}Joint3" value="0"/>
|
||||
<joint name="${device_name}Joint4" value="0"/>
|
||||
<joint name="${device_name}Joint5" value="0"/>
|
||||
<joint name="${device_name}Joint6" value="0"/>
|
||||
</group_state>
|
||||
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
|
||||
<virtual_joint name="${device_name}virtual_joint" type="fixed" parent_frame="world" child_link="${device_name}base_link"/>
|
||||
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
|
||||
<disable_collisions link1="${device_name}J1_1" link2="${device_name}J2_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="${device_name}J1_1" link2="${device_name}J3_1" reason="Never"/>
|
||||
<disable_collisions link1="${device_name}J1_1" link2="${device_name}J4_1" reason="Never"/>
|
||||
<disable_collisions link1="${device_name}J1_1" link2="${device_name}base_link" reason="Adjacent"/>
|
||||
<disable_collisions link1="${device_name}J2_1" link2="${device_name}J3_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="${device_name}J3_1" link2="${device_name}J4_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="${device_name}J3_1" link2="${device_name}J5_1" reason="Never"/>
|
||||
<disable_collisions link1="${device_name}J3_1" link2="${device_name}J6_1" reason="Never"/>
|
||||
<disable_collisions link1="${device_name}J3_1" link2="${device_name}base_link" reason="Never"/>
|
||||
<disable_collisions link1="${device_name}J4_1" link2="${device_name}J5_1" reason="Adjacent"/>
|
||||
<disable_collisions link1="${device_name}J4_1" link2="${device_name}J6_1" reason="Never"/>
|
||||
<disable_collisions link1="${device_name}J5_1" link2="${device_name}J6_1" reason="Adjacent"/>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
@@ -0,0 +1,8 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="dummy2" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<material name="silver">
|
||||
<color rgba="0.700 0.700 0.700 1.000"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
||||
@@ -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": "J6_1"
|
||||
}
|
||||
}
|
||||
51
unilabos/device_mesh/devices/dummy2_robot/config/moveit.rviz
Normal file
51
unilabos/device_mesh/devices/dummy2_robot/config/moveit.rviz
Normal file
@@ -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
|
||||
@@ -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
|
||||
@@ -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 }
|
||||
@@ -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
|
||||
@@ -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
|
||||
@@ -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
|
||||
237
unilabos/device_mesh/devices/dummy2_robot/dummy2.xacro
Normal file
237
unilabos/device_mesh/devices/dummy2_robot/dummy2.xacro
Normal file
@@ -0,0 +1,237 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="dummy2" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/materials.xacro" />
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/dummy2.trans" />
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/dummy2.gazebo" />
|
||||
<link name="world" />
|
||||
<joint name="world_joint" type="fixed">
|
||||
<parent link="world" />
|
||||
<child link = "base_link" />
|
||||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||
</joint>
|
||||
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<origin xyz="0.00010022425916431473 -6.186605493937309e-05 0.05493640543484716" rpy="0 0 0"/>
|
||||
<mass value="1.2152141810431654"/>
|
||||
<inertia ixx="0.002105" iyy="0.002245" izz="0.002436" ixy="-0.0" iyz="-1.1e-05" ixz="0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J1_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.00617659688932347 0.007029599744830012 0.012866826083045027" rpy="0 0 0"/>
|
||||
<mass value="0.1332774369186824"/>
|
||||
<inertia ixx="6e-05" iyy="5e-05" izz="8.8e-05" ixy="2.1e-05" iyz="-1.4e-05" ixz="8e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.0001 0.000289 -0.097579" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J1_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.0001 0.000289 -0.097579" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J1_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J2_1">
|
||||
<inertial>
|
||||
<origin xyz="0.019335709221765855 0.0019392793940843159 0.07795928103332703" rpy="0 0 0"/>
|
||||
<mass value="1.9268013917303417"/>
|
||||
<inertia ixx="0.006165" iyy="0.006538" izz="0.00118" ixy="-3e-06" iyz="4.7e-05" ixz="0.0007"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0.011539 -0.034188 -0.12478" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J2_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.011539 -0.034188 -0.12478" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J2_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J3_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.010672101243726572 -0.02723871972304964 0.04876701375652198" rpy="0 0 0"/>
|
||||
<mass value="0.30531962155452225"/>
|
||||
<inertia ixx="0.00029" iyy="0.000238" izz="0.000191" ixy="-1.3e-05" iyz="4.1e-05" ixz="3e-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.023811 -0.034188 -0.28278" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J3_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.023811 -0.034188 -0.28278" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J3_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J4_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.005237398377441591 0.06002028183461833 0.0005891767740203724" rpy="0 0 0"/>
|
||||
<mass value="0.14051172121899885"/>
|
||||
<inertia ixx="0.000245" iyy="7.9e-05" izz="0.00027" ixy="1.6e-05" iyz="-2e-06" ixz="1e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.010649 -0.038288 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J4_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.010649 -0.038288 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J4_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J5_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.014389813882964664 0.07305218143664277 -0.0009243405950149497" rpy="0 0 0"/>
|
||||
<mass value="0.7783315754227634"/>
|
||||
<inertia ixx="0.000879" iyy="0.000339" izz="0.000964" ixy="0.000146" iyz="1e-06" ixz="-5e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.031949 -0.148289 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J5_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.031949 -0.148289 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J5_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J6_1">
|
||||
<inertial>
|
||||
<origin xyz="3.967160300787087e-07 0.0004995066702210837 1.4402781733924286e-07" rpy="0 0 0"/>
|
||||
<mass value="0.0020561527568204153"/>
|
||||
<inertia ixx="0.0" iyy="0.0" izz="0.0" ixy="0.0" iyz="0.0" ixz="0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.012127 -0.267789 -0.344021" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J6_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.012127 -0.267789 -0.344021" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J6_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="camera">
|
||||
<inertial>
|
||||
<origin xyz="-0.0006059984983273845 0.0005864706438700462 0.04601775357664567" rpy="0 0 0"/>
|
||||
<mass value="0.21961029019655884"/>
|
||||
<inertia ixx="2.9e-05" iyy="0.000206" izz="0.000198" ixy="-0.0" iyz="2e-06" ixz="-0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.012661 -0.239774 -0.37985" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/camera_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.012661 -0.239774 -0.37985" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/camera_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="Joint1" type="revolute">
|
||||
<origin xyz="0.0001 -0.000289 0.097579" rpy="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="J1_1"/>
|
||||
<axis xyz="-0.0 -0.0 1.0"/>
|
||||
<limit upper="3.054326" lower="-3.054326" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint2" type="revolute">
|
||||
<origin xyz="-0.011639 0.034477 0.027201" rpy="0 0 0"/>
|
||||
<parent link="J1_1"/>
|
||||
<child link="J2_1"/>
|
||||
<axis xyz="1.0 0.0 -0.0"/>
|
||||
<limit upper="1.308997" lower="-2.007129" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint3" type="revolute">
|
||||
<origin xyz="0.03535 0.0 0.158" rpy="0 0 0"/>
|
||||
<parent link="J2_1"/>
|
||||
<child link="J3_1"/>
|
||||
<axis xyz="-1.0 0.0 -0.0"/>
|
||||
<limit upper="1.570796" lower="-1.047198" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint4" type="revolute">
|
||||
<origin xyz="-0.013162 0.0041 0.062466" rpy="0 0 0"/>
|
||||
<parent link="J3_1"/>
|
||||
<child link="J4_1"/>
|
||||
<axis xyz="0.0 1.0 -0.0"/>
|
||||
<limit upper="3.141593" lower="-3.141593" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint5" type="revolute">
|
||||
<origin xyz="0.0213 0.110001 0.0" rpy="0 0 0"/>
|
||||
<parent link="J4_1"/>
|
||||
<child link="J5_1"/>
|
||||
<axis xyz="-1.0 -0.0 -0.0"/>
|
||||
<limit upper="2.094395" lower="-1.919862" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint6" type="continuous">
|
||||
<origin xyz="-0.019822 0.1195 -0.001225" rpy="0 0 0"/>
|
||||
<parent link="J5_1"/>
|
||||
<child link="J6_1"/>
|
||||
<axis xyz="0.0 -1.0 0.0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="camera" type="fixed">
|
||||
<origin xyz="-0.019988 0.091197 0.024883" rpy="0 0 0"/>
|
||||
<parent link="J5_1"/>
|
||||
<child link="camera"/>
|
||||
<axis xyz="1.0 -0.0 0.0"/>
|
||||
<limit upper="0.0" lower="0.0" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
</robot>
|
||||
37
unilabos/device_mesh/devices/dummy2_robot/joint_limit.yaml
Normal file
37
unilabos/device_mesh/devices/dummy2_robot/joint_limit.yaml
Normal file
@@ -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
|
||||
249
unilabos/device_mesh/devices/dummy2_robot/macro_device.xacro
Normal file
249
unilabos/device_mesh/devices/dummy2_robot/macro_device.xacro
Normal file
@@ -0,0 +1,249 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="dummy2" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
|
||||
<xacro:macro name="dummy2_robot" params="mesh_path:='' parent_link:='' station_name:='' device_name:='' x:=0 y:=0 z:=0 rx:=0 ry:=0 r:=0">
|
||||
|
||||
<xacro:include filename="${mesh_path}/devices/dummy2_robot/config/materials.xacro" />
|
||||
<xacro:include filename="${mesh_path}/devices/dummy2_robot/config/dummy2.trans" />
|
||||
|
||||
<joint name="${station_name}${device_name}base_link_joint" type="fixed">
|
||||
<origin xyz="${x} ${y} ${z}" rpy="${rx} ${ry} ${r}" />
|
||||
<parent link="${parent_link}"/>
|
||||
<child link="${station_name}${device_name}device_link"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="${station_name}${device_name}device_link"/>
|
||||
<joint name="${station_name}${device_name}device_link_joint" type="fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="${station_name}${device_name}device_link"/>
|
||||
<child link="${station_name}${device_name}base_link"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="${station_name}${device_name}base_link">
|
||||
<inertial>
|
||||
<origin xyz="0.00010022425916431473 -6.186605493937309e-05 0.05493640543484716" rpy="0 0 0"/>
|
||||
<mass value="1.2152141810431654"/>
|
||||
<inertia ixx="0.002105" iyy="0.002245" izz="0.002436" ixy="-0.0" iyz="-1.1e-05" ixz="0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}J1_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.00617659688932347 0.007029599744830012 0.012866826083045027" rpy="0 0 0"/>
|
||||
<mass value="0.1332774369186824"/>
|
||||
<inertia ixx="6e-05" iyy="5e-05" izz="8.8e-05" ixy="2.1e-05" iyz="-1.4e-05" ixz="8e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.0001 0.000289 -0.097579" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J1_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.0001 0.000289 -0.097579" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J1_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}J2_1">
|
||||
<inertial>
|
||||
<origin xyz="0.019335709221765855 0.0019392793940843159 0.07795928103332703" rpy="0 0 0"/>
|
||||
<mass value="1.9268013917303417"/>
|
||||
<inertia ixx="0.006165" iyy="0.006538" izz="0.00118" ixy="-3e-06" iyz="4.7e-05" ixz="0.0007"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0.011539 -0.034188 -0.12478" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J2_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.011539 -0.034188 -0.12478" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J2_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}J3_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.010672101243726572 -0.02723871972304964 0.04876701375652198" rpy="0 0 0"/>
|
||||
<mass value="0.30531962155452225"/>
|
||||
<inertia ixx="0.00029" iyy="0.000238" izz="0.000191" ixy="-1.3e-05" iyz="4.1e-05" ixz="3e-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.023811 -0.034188 -0.28278" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J3_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.023811 -0.034188 -0.28278" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J3_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}J4_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.005237398377441591 0.06002028183461833 0.0005891767740203724" rpy="0 0 0"/>
|
||||
<mass value="0.14051172121899885"/>
|
||||
<inertia ixx="0.000245" iyy="7.9e-05" izz="0.00027" ixy="1.6e-05" iyz="-2e-06" ixz="1e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.010649 -0.038288 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J4_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.010649 -0.038288 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J4_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}J5_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.014389813882964664 0.07305218143664277 -0.0009243405950149497" rpy="0 0 0"/>
|
||||
<mass value="0.7783315754227634"/>
|
||||
<inertia ixx="0.000879" iyy="0.000339" izz="0.000964" ixy="0.000146" iyz="1e-06" ixz="-5e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.031949 -0.148289 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J5_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.031949 -0.148289 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J5_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}J6_1">
|
||||
<inertial>
|
||||
<origin xyz="3.967160300787087e-07 0.0004995066702210837 1.4402781733924286e-07" rpy="0 0 0"/>
|
||||
<mass value="0.0020561527568204153"/>
|
||||
<inertia ixx="0.0" iyy="0.0" izz="0.0" ixy="0.0" iyz="0.0" ixz="0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.012127 -0.267789 -0.344021" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J6_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.012127 -0.267789 -0.344021" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/J6_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="${station_name}${device_name}camera">
|
||||
<inertial>
|
||||
<origin xyz="-0.0006059984983273845 0.0005864706438700462 0.04601775357664567" rpy="0 0 0"/>
|
||||
<mass value="0.21961029019655884"/>
|
||||
<inertia ixx="2.9e-05" iyy="0.000206" izz="0.000198" ixy="-0.0" iyz="2e-06" ixz="-0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.012661 -0.239774 -0.37985" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/camera_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.012661 -0.239774 -0.37985" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://${mesh_path}/devices/dummy2_robot/meshes/camera_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${station_name}${device_name}Joint1" type="revolute">
|
||||
<origin xyz="0.0001 -0.000289 0.097579" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}base_link"/>
|
||||
<child link="${station_name}${device_name}J1_1"/>
|
||||
<axis xyz="-0.0 -0.0 1.0"/>
|
||||
<limit upper="3.054326" lower="-3.054326" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${station_name}${device_name}Joint2" type="revolute">
|
||||
<origin xyz="-0.011639 0.034477 0.027201" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}J1_1"/>
|
||||
<child link="${station_name}${device_name}J2_1"/>
|
||||
<axis xyz="1.0 0.0 -0.0"/>
|
||||
<limit upper="1.308997" lower="-2.007129" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${station_name}${device_name}Joint3" type="revolute">
|
||||
<origin xyz="0.03535 0.0 0.158" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}J2_1"/>
|
||||
<child link="${station_name}${device_name}J3_1"/>
|
||||
<axis xyz="-1.0 0.0 -0.0"/>
|
||||
<limit upper="1.570796" lower="-1.047198" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${station_name}${device_name}Joint4" type="revolute">
|
||||
<origin xyz="-0.013162 0.0041 0.062466" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}J3_1"/>
|
||||
<child link="${station_name}${device_name}J4_1"/>
|
||||
<axis xyz="0.0 1.0 -0.0"/>
|
||||
<limit upper="3.141593" lower="-3.141593" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${station_name}${device_name}Joint5" type="revolute">
|
||||
<origin xyz="0.0213 0.110001 0.0" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}J4_1"/>
|
||||
<child link="${station_name}${device_name}J5_1"/>
|
||||
<axis xyz="-1.0 -0.0 -0.0"/>
|
||||
<limit upper="2.094395" lower="-1.919862" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${station_name}${device_name}Joint6" type="continuous">
|
||||
<origin xyz="-0.019822 0.1195 -0.001225" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}J5_1"/>
|
||||
<child link="${station_name}${device_name}J6_1"/>
|
||||
<axis xyz="0.0 -1.0 0.0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${station_name}${device_name}camera" type="fixed">
|
||||
<origin xyz="-0.019988 0.091197 0.024883" rpy="0 0 0"/>
|
||||
<parent link="${station_name}${device_name}J5_1"/>
|
||||
<child link="${station_name}${device_name}camera"/>
|
||||
<axis xyz="1.0 -0.0 0.0"/>
|
||||
<limit upper="0.0" lower="0.0" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J1_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J1_1.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J2_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J2_1.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J3_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J3_1.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J4_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J4_1.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J5_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J5_1.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J6_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/J6_1.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/base_link.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/base_link.stl
Normal file
Binary file not shown.
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/camera_1.stl
Normal file
BIN
unilabos/device_mesh/devices/dummy2_robot/meshes/camera_1.stl
Normal file
Binary file not shown.
237
unilabos/device_mesh/devices/dummy2_robot/meshes/dummy2.xacro
Normal file
237
unilabos/device_mesh/devices/dummy2_robot/meshes/dummy2.xacro
Normal file
@@ -0,0 +1,237 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="dummy2" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/materials.xacro" />
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/dummy2.trans" />
|
||||
<xacro:include filename="$(find dummy2_description)/urdf/dummy2.gazebo" />
|
||||
<link name="world" />
|
||||
<joint name="world_joint" type="fixed">
|
||||
<parent link="world" />
|
||||
<child link = "base_link" />
|
||||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||
</joint>
|
||||
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<origin xyz="0.00010022425916431473 -6.186605493937309e-05 0.05493640543484716" rpy="0 0 0"/>
|
||||
<mass value="1.2152141810431654"/>
|
||||
<inertia ixx="0.002105" iyy="0.002245" izz="0.002436" ixy="-0.0" iyz="-1.1e-05" ixz="0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J1_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.00617659688932347 0.007029599744830012 0.012866826083045027" rpy="0 0 0"/>
|
||||
<mass value="0.1332774369186824"/>
|
||||
<inertia ixx="6e-05" iyy="5e-05" izz="8.8e-05" ixy="2.1e-05" iyz="-1.4e-05" ixz="8e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.0001 0.000289 -0.097579" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J1_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.0001 0.000289 -0.097579" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J1_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J2_1">
|
||||
<inertial>
|
||||
<origin xyz="0.019335709221765855 0.0019392793940843159 0.07795928103332703" rpy="0 0 0"/>
|
||||
<mass value="1.9268013917303417"/>
|
||||
<inertia ixx="0.006165" iyy="0.006538" izz="0.00118" ixy="-3e-06" iyz="4.7e-05" ixz="0.0007"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0.011539 -0.034188 -0.12478" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J2_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.011539 -0.034188 -0.12478" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J2_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J3_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.010672101243726572 -0.02723871972304964 0.04876701375652198" rpy="0 0 0"/>
|
||||
<mass value="0.30531962155452225"/>
|
||||
<inertia ixx="0.00029" iyy="0.000238" izz="0.000191" ixy="-1.3e-05" iyz="4.1e-05" ixz="3e-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.023811 -0.034188 -0.28278" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J3_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.023811 -0.034188 -0.28278" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J3_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J4_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.005237398377441591 0.06002028183461833 0.0005891767740203724" rpy="0 0 0"/>
|
||||
<mass value="0.14051172121899885"/>
|
||||
<inertia ixx="0.000245" iyy="7.9e-05" izz="0.00027" ixy="1.6e-05" iyz="-2e-06" ixz="1e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.010649 -0.038288 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J4_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.010649 -0.038288 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J4_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J5_1">
|
||||
<inertial>
|
||||
<origin xyz="-0.014389813882964664 0.07305218143664277 -0.0009243405950149497" rpy="0 0 0"/>
|
||||
<mass value="0.7783315754227634"/>
|
||||
<inertia ixx="0.000879" iyy="0.000339" izz="0.000964" ixy="0.000146" iyz="1e-06" ixz="-5e-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.031949 -0.148289 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J5_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.031949 -0.148289 -0.345246" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J5_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="J6_1">
|
||||
<inertial>
|
||||
<origin xyz="3.967160300787087e-07 0.0004995066702210837 1.4402781733924286e-07" rpy="0 0 0"/>
|
||||
<mass value="0.0020561527568204153"/>
|
||||
<inertia ixx="0.0" iyy="0.0" izz="0.0" ixy="0.0" iyz="0.0" ixz="0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.012127 -0.267789 -0.344021" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J6_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.012127 -0.267789 -0.344021" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/J6_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="camera">
|
||||
<inertial>
|
||||
<origin xyz="-0.0006059984983273845 0.0005864706438700462 0.04601775357664567" rpy="0 0 0"/>
|
||||
<mass value="0.21961029019655884"/>
|
||||
<inertia ixx="2.9e-05" iyy="0.000206" izz="0.000198" ixy="-0.0" iyz="2e-06" ixz="-0.0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="-0.012661 -0.239774 -0.37985" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/camera_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.012661 -0.239774 -0.37985" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dummy2_description)/meshes/camera_1.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="Joint1" type="revolute">
|
||||
<origin xyz="0.0001 -0.000289 0.097579" rpy="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="J1_1"/>
|
||||
<axis xyz="-0.0 -0.0 1.0"/>
|
||||
<limit upper="3.054326" lower="-3.054326" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint2" type="revolute">
|
||||
<origin xyz="-0.011639 0.034477 0.027201" rpy="0 0 0"/>
|
||||
<parent link="J1_1"/>
|
||||
<child link="J2_1"/>
|
||||
<axis xyz="1.0 0.0 -0.0"/>
|
||||
<limit upper="1.308997" lower="-2.007129" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint3" type="revolute">
|
||||
<origin xyz="0.03535 0.0 0.158" rpy="0 0 0"/>
|
||||
<parent link="J2_1"/>
|
||||
<child link="J3_1"/>
|
||||
<axis xyz="-1.0 0.0 -0.0"/>
|
||||
<limit upper="1.570796" lower="-1.047198" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint4" type="revolute">
|
||||
<origin xyz="-0.013162 0.0041 0.062466" rpy="0 0 0"/>
|
||||
<parent link="J3_1"/>
|
||||
<child link="J4_1"/>
|
||||
<axis xyz="0.0 1.0 -0.0"/>
|
||||
<limit upper="3.141593" lower="-3.141593" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint5" type="revolute">
|
||||
<origin xyz="0.0213 0.110001 0.0" rpy="0 0 0"/>
|
||||
<parent link="J4_1"/>
|
||||
<child link="J5_1"/>
|
||||
<axis xyz="-1.0 -0.0 -0.0"/>
|
||||
<limit upper="2.094395" lower="-1.919862" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
<joint name="Joint6" type="continuous">
|
||||
<origin xyz="-0.019822 0.1195 -0.001225" rpy="0 0 0"/>
|
||||
<parent link="J5_1"/>
|
||||
<child link="J6_1"/>
|
||||
<axis xyz="0.0 -1.0 0.0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="camera" type="fixed">
|
||||
<origin xyz="-0.019988 0.091197 0.024883" rpy="0 0 0"/>
|
||||
<parent link="J5_1"/>
|
||||
<child link="camera"/>
|
||||
<axis xyz="1.0 -0.0 0.0"/>
|
||||
<limit upper="0.0" lower="0.0" effort="100" velocity="100"/>
|
||||
</joint>
|
||||
|
||||
</robot>
|
||||
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/base_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/base_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/x_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/x_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/y_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/y_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/z_link.STL
Normal file → Executable file
0
unilabos/device_mesh/devices/liquid_transform_xyz/meshes/z_link.STL
Normal file → Executable file
@@ -14,6 +14,7 @@ from launch_ros.parameter_descriptions import ParameterFile
|
||||
from unilabos.registry.registry import lab_registry
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
|
||||
def get_pattern_matches(folder, pattern):
|
||||
"""Given all the files in the folder, find those that match the pattern.
|
||||
|
||||
@@ -51,7 +52,7 @@ class ResourceVisualization:
|
||||
self.launch_description = LaunchDescription()
|
||||
self.resource_dict = resource
|
||||
self.resource_model = {}
|
||||
self.resource_type = ['deck', 'plate', 'container']
|
||||
self.resource_type = ['deck', 'plate', 'container', 'tip_rack']
|
||||
self.mesh_path = Path(__file__).parent.absolute()
|
||||
self.enable_rviz = enable_rviz
|
||||
registry = lab_registry
|
||||
@@ -128,9 +129,9 @@ class ResourceVisualization:
|
||||
# if node["parent"] is not None:
|
||||
# new_dev.set("station_name", node["parent"]+'_')
|
||||
|
||||
new_dev.set("x",str(float(node["position"]["x"])/1000))
|
||||
new_dev.set("y",str(float(node["position"]["y"])/1000))
|
||||
new_dev.set("z",str(float(node["position"]["z"])/1000))
|
||||
new_dev.set("x",str(float(node["position"]["position"]["x"])/1000))
|
||||
new_dev.set("y",str(float(node["position"]["position"]["y"])/1000))
|
||||
new_dev.set("z",str(float(node["position"]["position"]["z"])/1000))
|
||||
if "rotation" in node["config"]:
|
||||
new_dev.set("rx",str(float(node["config"]["rotation"]["x"])))
|
||||
new_dev.set("ry",str(float(node["config"]["rotation"]["y"])))
|
||||
@@ -140,7 +141,7 @@ class ResourceVisualization:
|
||||
new_dev.set(key, str(value))
|
||||
|
||||
# 添加ros2_controller
|
||||
if node['class'].startswith('moveit.'):
|
||||
if node['class'].find('moveit.')!= -1:
|
||||
new_include_controller = etree.SubElement(self.root, f"{{{xacro_uri}}}include")
|
||||
new_include_controller.set("filename", f"{str(self.mesh_path)}/devices/{model_config['mesh']}/config/macro.ros2_control.xacro")
|
||||
new_controller = etree.SubElement(self.root, f"{{{xacro_uri}}}{model_config['mesh']}_ros2_control")
|
||||
@@ -203,7 +204,24 @@ class ResourceVisualization:
|
||||
Returns:
|
||||
LaunchDescription: launch描述对象
|
||||
"""
|
||||
moveit_configs_utils_path = Path(get_package_share_directory("moveit_configs_utils"))
|
||||
# 检查ROS 2环境变量
|
||||
if "AMENT_PREFIX_PATH" not in os.environ:
|
||||
raise OSError(
|
||||
"ROS 2环境未正确设置。需要设置 AMENT_PREFIX_PATH 环境变量。\n"
|
||||
"请确保:\n"
|
||||
"1. 已安装ROS 2 (推荐使用 ros-humble-desktop-full)\n"
|
||||
"2. 已激活Conda环境: conda activate unilab\n"
|
||||
"3. 或手动source ROS 2 setup文件: source /opt/ros/humble/setup.bash\n"
|
||||
"4. 或者使用 --backend simple 参数跳过ROS依赖"
|
||||
)
|
||||
|
||||
try:
|
||||
moveit_configs_utils_path = Path(get_package_share_directory("moveit_configs_utils"))
|
||||
except Exception as e:
|
||||
raise OSError(
|
||||
f"无法找到moveit_configs_utils包。请确保ROS 2和MoveIt 2已正确安装。\n"
|
||||
f"原始错误: {e}"
|
||||
)
|
||||
default_folder = moveit_configs_utils_path / "default_configs"
|
||||
planning_pattern = re.compile("^(.*)_planning.yaml$")
|
||||
pipelines = []
|
||||
@@ -264,7 +282,8 @@ class ResourceVisualization:
|
||||
parameters=[
|
||||
{"robot_description": robot_description},
|
||||
ros2_controllers,
|
||||
]
|
||||
],
|
||||
env=dict(os.environ)
|
||||
)
|
||||
)
|
||||
for controller in self.moveit_controllers_yaml['moveit_simple_controller_manager']['controller_names']:
|
||||
@@ -274,6 +293,7 @@ class ResourceVisualization:
|
||||
executable="spawner",
|
||||
arguments=[f"{controller}", "--controller-manager", f"controller_manager"],
|
||||
output="screen",
|
||||
env=dict(os.environ)
|
||||
)
|
||||
)
|
||||
controllers.append(
|
||||
@@ -282,6 +302,7 @@ class ResourceVisualization:
|
||||
executable="spawner",
|
||||
arguments=["joint_state_broadcaster", "--controller-manager", f"controller_manager"],
|
||||
output="screen",
|
||||
env=dict(os.environ)
|
||||
)
|
||||
)
|
||||
for i in controllers:
|
||||
@@ -300,7 +321,8 @@ class ResourceVisualization:
|
||||
'use_sim_time': False
|
||||
},
|
||||
# kinematics_dict
|
||||
]
|
||||
],
|
||||
env=dict(os.environ)
|
||||
)
|
||||
|
||||
|
||||
@@ -331,7 +353,8 @@ class ResourceVisualization:
|
||||
package='moveit_ros_move_group',
|
||||
executable='move_group',
|
||||
output='screen',
|
||||
parameters=moveit_params
|
||||
parameters=moveit_params,
|
||||
env=dict(os.environ)
|
||||
)
|
||||
|
||||
|
||||
@@ -354,7 +377,8 @@ class ResourceVisualization:
|
||||
robot_description_planning,
|
||||
planning_pipelines,
|
||||
|
||||
]
|
||||
],
|
||||
env=dict(os.environ)
|
||||
)
|
||||
self.launch_description.add_action(rviz_node)
|
||||
|
||||
|
||||
BIN
unilabos/device_mesh/resources/bottle/meshes/bottle.stl
Normal file
BIN
unilabos/device_mesh/resources/bottle/meshes/bottle.stl
Normal file
Binary file not shown.
11
unilabos/device_mesh/resources/bottle/modal.xacro
Normal file
11
unilabos/device_mesh/resources/bottle/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="bottle">
|
||||
<link name='bottle'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/bottle.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
Binary file not shown.
11
unilabos/device_mesh/resources/bottle_container/modal.xacro
Normal file
11
unilabos/device_mesh/resources/bottle_container/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="bottle_container">
|
||||
<link name='bottle_container'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/bottle_container.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
BIN
unilabos/device_mesh/resources/plate_96/meshes/plate_96.stl
Normal file
BIN
unilabos/device_mesh/resources/plate_96/meshes/plate_96.stl
Normal file
Binary file not shown.
11
unilabos/device_mesh/resources/plate_96/modal.xacro
Normal file
11
unilabos/device_mesh/resources/plate_96/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="plate_96">
|
||||
<link name='plate_96'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/plate_96.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
BIN
unilabos/device_mesh/resources/tip/meshes/tip.stl
Normal file
BIN
unilabos/device_mesh/resources/tip/meshes/tip.stl
Normal file
Binary file not shown.
11
unilabos/device_mesh/resources/tip/modal.xacro
Normal file
11
unilabos/device_mesh/resources/tip/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="tip">
|
||||
<link name='tip'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/tip.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
Binary file not shown.
11
unilabos/device_mesh/resources/tiprack_box/modal.xacro
Normal file
11
unilabos/device_mesh/resources/tiprack_box/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="tiprack_box">
|
||||
<link name='tiprack_box'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/tiprack_box.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
BIN
unilabos/device_mesh/resources/tube/meshes/tube.stl
Normal file
BIN
unilabos/device_mesh/resources/tube/meshes/tube.stl
Normal file
Binary file not shown.
11
unilabos/device_mesh/resources/tube/modal.xacro
Normal file
11
unilabos/device_mesh/resources/tube/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="tube">
|
||||
<link name='tube'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/tube.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
Binary file not shown.
11
unilabos/device_mesh/resources/tube_container/modal.xacro
Normal file
11
unilabos/device_mesh/resources/tube_container/modal.xacro
Normal file
@@ -0,0 +1,11 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="tube_container">
|
||||
<link name='tube_container'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh filename="meshes/tube_container.stl"/>
|
||||
</geometry>
|
||||
<material name="clay" />
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
@@ -5,11 +5,13 @@ Panels:
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /TF1/Tree1
|
||||
- /PlanningScene1
|
||||
- /PlanningScene1/Scene Geometry1
|
||||
- /MotionPlanning1/Scene Geometry1
|
||||
- /MotionPlanning1/Scene Robot1
|
||||
- /MotionPlanning1/Planning Request1
|
||||
Splitter Ratio: 0.5016146302223206
|
||||
Tree Height: 1112
|
||||
Tree Height: 563
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
@@ -91,7 +93,7 @@ Visualization Manager:
|
||||
Planning Scene Topic: /monitored_planning_scene
|
||||
Robot Description: robot_description
|
||||
Scene Geometry:
|
||||
Scene Alpha: 0.8999999761581421
|
||||
Scene Alpha: 1
|
||||
Scene Color: 50; 230; 50
|
||||
Scene Display Time: 0.009999999776482582
|
||||
Show Scene Geometry: true
|
||||
@@ -567,25 +569,25 @@ Visualization Manager:
|
||||
Pitch: 0.4297958016395569
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.3525616228580475
|
||||
Yaw: 0.36756160855293274
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 2032
|
||||
Height: 1088
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
MotionPlanning:
|
||||
collapsed: true
|
||||
collapsed: false
|
||||
MotionPlanning - Trajectory Slider:
|
||||
collapsed: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000003a30000079bfc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000027000004c60000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000007a00fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000004f9000002c9000002b800ffffff000000010000010f00000387fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000003870000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000bc50000079b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730000000000ffffffff0000000000000000
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000003a30000040bfc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000001700000271000000ca00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004200fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000028e000001940000018900ffffff000000010000010f00000387fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000387000000a600fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004110000040b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730000000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: true
|
||||
Width: 3956
|
||||
X: 140
|
||||
Y: 54
|
||||
Width: 1978
|
||||
X: 70
|
||||
Y: 27
|
||||
|
||||
Reference in New Issue
Block a user