mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2026-02-12 02:35:11 +00:00
Device visualization (#67)
* Update README and MQTTClient for installation instructions and code improvements * feat: 支持local_config启动 add: 增加对crt path的说明,为传入config.py的相对路径 move: web component * add: registry description * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * feat: node_info_update srv fix: OTDeck cant create * close #12 feat: slave node registry * feat: show machine name fix: host node registry not uploaded * feat: add hplc registry * feat: add hplc registry * fix: hplc status typo * fix: devices/ * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * fix: device.class possible null * fix: HPLC additions with online service * fix: slave mode spin not working * fix: slave mode spin not working * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * feat: 多ProtocolNode 允许子设备ID相同 feat: 上报发现的ActionClient feat: Host重启动,通过discover机制要求slaveNode重新注册,实现信息及时上报 * feat: 支持env设置config * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * Device visualization (#14) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: missing hostname in devices_names fix: upload_file for model file * fix: missing paho-mqtt package bump version to 0.9.0 * fix startup add ResourceCreateFromOuter.action * fix type hint * update actions * update actions * host node add_resource_from_outer fix cmake list * pass device config to device class * add: bind_parent_ids to resource create action fix: message convert string * fix: host node should not be re_discovered * feat: resource tracker support dict * feat: add more necessary params * feat: fix boolean null in registry action data * feat: add outer resource * 编写mesh添加action * feat: append resource * add action * feat: vis 2d for plr * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate * Device visualization (#22) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * 编写mesh添加action * add action * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: multi channel * fix: aspirate * fix: aspirate * fix: aspirate * fix: aspirate * 提交 * fix: jobadd * fix: jobadd * fix: msg converter * tijiao * add resource creat easy action * identify debug msg * mq client id * 提取lh的joint发布 * unify liquid_handler definition * 修改物料跟随与物料添加逻辑 修改物料跟随与物料添加逻辑 将joint_publisher类移出lh的backends,但仍需要对lh的backends进行一些改写 * Revert "修改物料跟随与物料添加逻辑" This reverts commit498c997ad7. * Reapply "修改物料跟随与物料添加逻辑" This reverts commit3a60d2ae81. * Revert "Merge remote-tracking branch 'upstream/dev' into device_visualization" This reverts commitfa727220af, reversing changes made to498c997ad7. * 修改物料放下时的方法,如果选择 修改物料放下时的方法, 如果选择drop_trash,则删除物料显示 如果选择drop,则让其解除连接 * unilab添加moveit启动 1,整合所有moveit节点到一个move_group中,并整合所有的controller依次激活 2,添加pymoveit2的节点,使用json可直接启动 3,修改机械臂规划方式,添加约束,让冗余关节不会进行过多移动 * 修改物体attach时,多次赋值当前时间导致卡顿问题, * Revert "修改物体attach时,多次赋值当前时间导致卡顿问题," This reverts commit56d45b94f5. * Reapply "修改物体attach时,多次赋值当前时间导致卡顿问题," This reverts commit07d9db20c3. * 添加缺少物料:"plate_well_G12", * add * fix tip resource data * liquid states * change to debug level * Revert "change to debug level" This reverts commit5d9953c3e5. * Reapply "change to debug level" This reverts commit2487bb6ffc. * fix tip resource data * add full device * add moveit yaml * 修复moveit 增加post_init阶段,给予ros_node反向 * remove necessary node * fix moveit action client * remove necessary imports * Update moveit_interface.py * fix handler_key uppercase * json add liquids * fix setup * add * change to "sources" and "targets" for lh * bump version * remove parent's parent link * change arm's name * change name * fix ik error * 修改moveit_interface,并在mqtt上报时发送一个时间戳 * 添加机械臂和移液站 * 添加 * 添加硬件 * update * 添加 --------- Co-authored-by: Harvey Que <Q-Query@outlook.com> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: Junhan Chang <changjh@pku.edu.cn>
This commit is contained in:
@@ -0,0 +1,174 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://wiki.ros.org/xacro">
|
||||
<!--
|
||||
NOTE the macros defined in this file are NOT part of the public API of this
|
||||
package. Users CANNOT rely on this file being available, or stored in
|
||||
this location. Nor can they rely on the existence of the two macros.
|
||||
The macros store the defined properties in the scope of the caller.
|
||||
However, users MUST NOT rely on these properties, their contents or their
|
||||
names.
|
||||
|
||||
Author: Chen Shichao
|
||||
-->
|
||||
<xacro:macro name="build_inertial" params="mass cog inertia">
|
||||
<inertial>
|
||||
<mass value="${mass}" />
|
||||
<origin
|
||||
xyz="${cog['x']} ${cog['y']} ${cog['z']}"
|
||||
rpy="0 0 0" />
|
||||
<inertia
|
||||
ixx="${inertia['ixx']}"
|
||||
ixy="${inertia['ixy']}"
|
||||
ixz="${inertia['ixz']}"
|
||||
iyy="${inertia['iyy']}"
|
||||
iyz="${inertia['iyz']}"
|
||||
izz="${inertia['izz']}" />
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="get_visual_params" params="name:=^ type:=^" >
|
||||
<xacro:property name="visual_params" value="${sec_mesh_files[name][type]}" scope="parent"/>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Simplification of getting meshes. Available types can be seen in the visual_parameters.yaml (At the time of writing: visual, collision) -->
|
||||
<xacro:macro name="get_mesh_path" params="name:=^ type:=^" >
|
||||
<xacro:get_visual_params />
|
||||
<xacro:if value="${force_abs_paths}">
|
||||
<xacro:property name="mesh" value="file://${mesh_path}/devices/elite_robot/${visual_params['mesh']['path']}" scope="parent"/>
|
||||
</xacro:if>
|
||||
<xacro:unless value="${force_abs_paths}">
|
||||
<xacro:property name="mesh" value="package://${visual_params['mesh']['package']}/${visual_params['mesh']['path']}" scope="parent"/>
|
||||
</xacro:unless>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="get_mesh" params="name type" >
|
||||
<xacro:get_mesh_path/>
|
||||
<mesh filename="${mesh}"/>
|
||||
</xacro:macro>
|
||||
|
||||
<xacro:macro name="read_model_data" params="joint_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file force_abs_paths mesh_path">
|
||||
|
||||
<xacro:property name="force_abs_paths" value="${force_abs_paths}" scope="parent"/>
|
||||
<!-- Read .yaml files from disk, load content into properties -->
|
||||
<xacro:property name="config_joint_limit_parameters" value="${xacro.load_yaml(joint_limits_parameters_file)}"/>
|
||||
<xacro:property name="config_kinematics_parameters" value="${xacro.load_yaml(kinematics_parameters_file)}"/>
|
||||
<xacro:property name="config_physical_parameters" value="${xacro.load_yaml(physical_parameters_file)}"/>
|
||||
<xacro:property name="config_visual_parameters" value="${xacro.load_yaml(visual_parameters_file)}"/>
|
||||
|
||||
<xacro:property name="mesh_path" value="${mesh_path}" scope="parent"/>
|
||||
|
||||
<!-- Extract subsections from yaml dictionaries -->
|
||||
<xacro:property name="sec_limits" value="${config_joint_limit_parameters['joint_limits']}"/>
|
||||
<xacro:property name="sec_dh_parameters" value="${config_physical_parameters['dh_parameters']}"/>
|
||||
<xacro:property name="sec_offsets" value="${config_physical_parameters['offsets']}"/>
|
||||
<xacro:property name="sec_inertia_parameters" value="${config_physical_parameters['inertia_parameters']}" />
|
||||
<xacro:property name="sec_mesh_files" value="${config_visual_parameters['mesh_files']}" scope="parent"/>
|
||||
<xacro:property name="sec_kinematics" value="${config_kinematics_parameters['kinematics']}" />
|
||||
|
||||
<!-- JOINTS LIMIT PARAMETERS -->
|
||||
<xacro:property name="shoulder_pan_lower_limit" value="${sec_limits['shoulder_pan_joint']['min_position']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_pan_upper_limit" value="${sec_limits['shoulder_pan_joint']['max_position']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_pan_velocity_limit" value="${sec_limits['shoulder_pan_joint']['max_velocity']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_pan_effort_limit" value="${sec_limits['shoulder_pan_joint']['max_effort']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_lift_lower_limit" value="${sec_limits['shoulder_lift_joint']['min_position']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_lift_upper_limit" value="${sec_limits['shoulder_lift_joint']['max_position']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_lift_velocity_limit" value="${sec_limits['shoulder_lift_joint']['max_velocity']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_lift_effort_limit" value="${sec_limits['shoulder_lift_joint']['max_effort']}" scope="parent"/>
|
||||
<xacro:property name="elbow_joint_lower_limit" value="${sec_limits['elbow_joint']['min_position']}" scope="parent"/>
|
||||
<xacro:property name="elbow_joint_upper_limit" value="${sec_limits['elbow_joint']['max_position']}" scope="parent"/>
|
||||
<xacro:property name="elbow_joint_velocity_limit" value="${sec_limits['elbow_joint']['max_velocity']}" scope="parent"/>
|
||||
<xacro:property name="elbow_joint_effort_limit" value="${sec_limits['elbow_joint']['max_effort']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_lower_limit" value="${sec_limits['wrist_1_joint']['min_position']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_upper_limit" value="${sec_limits['wrist_1_joint']['max_position']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_velocity_limit" value="${sec_limits['wrist_1_joint']['max_velocity']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_effort_limit" value="${sec_limits['wrist_1_joint']['max_effort']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_lower_limit" value="${sec_limits['wrist_2_joint']['min_position']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_upper_limit" value="${sec_limits['wrist_2_joint']['max_position']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_velocity_limit" value="${sec_limits['wrist_2_joint']['max_velocity']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_effort_limit" value="${sec_limits['wrist_2_joint']['max_effort']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_lower_limit" value="${sec_limits['wrist_3_joint']['min_position']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_upper_limit" value="${sec_limits['wrist_3_joint']['max_position']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_velocity_limit" value="${sec_limits['wrist_3_joint']['max_velocity']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_effort_limit" value="${sec_limits['wrist_3_joint']['max_effort']}" scope="parent"/>
|
||||
|
||||
<!-- DH PARAMETERS -->
|
||||
<xacro:property name="d1" value="${sec_dh_parameters['d1']}" scope="parent"/>
|
||||
<xacro:property name="a2" value="${sec_dh_parameters['a2']}" scope="parent"/>
|
||||
<xacro:property name="a3" value="${sec_dh_parameters['a3']}" scope="parent"/>
|
||||
<xacro:property name="d4" value="${sec_dh_parameters['d4']}" scope="parent"/>
|
||||
<xacro:property name="d5" value="${sec_dh_parameters['d5']}" scope="parent"/>
|
||||
<xacro:property name="d6" value="${sec_dh_parameters['d6']}" scope="parent"/>
|
||||
|
||||
<!-- kinematics -->
|
||||
<xacro:property name="shoulder_x" value="${sec_kinematics['shoulder']['x']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_y" value="${sec_kinematics['shoulder']['y']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_z" value="${sec_kinematics['shoulder']['z']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_roll" value="${sec_kinematics['shoulder']['roll']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_pitch" value="${sec_kinematics['shoulder']['pitch']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_yaw" value="${sec_kinematics['shoulder']['yaw']}" scope="parent"/>
|
||||
|
||||
<xacro:property name="upperarm_x" value="${sec_kinematics['upperarm']['x']}" scope="parent"/>
|
||||
<xacro:property name="upperarm_y" value="${sec_kinematics['upperarm']['y']}" scope="parent"/>
|
||||
<xacro:property name="upperarm_z" value="${sec_kinematics['upperarm']['z']}" scope="parent"/>
|
||||
<xacro:property name="upperarm_roll" value="${sec_kinematics['upperarm']['roll']}" scope="parent"/>
|
||||
<xacro:property name="upperarm_pitch" value="${sec_kinematics['upperarm']['pitch']}" scope="parent"/>
|
||||
<xacro:property name="upperarm_yaw" value="${sec_kinematics['upperarm']['yaw']}" scope="parent"/>
|
||||
|
||||
<xacro:property name="forearm_x" value="${sec_kinematics['forearm']['x']}" scope="parent"/>
|
||||
<xacro:property name="forearm_y" value="${sec_kinematics['forearm']['y']}" scope="parent"/>
|
||||
<xacro:property name="forearm_z" value="${sec_kinematics['forearm']['z']}" scope="parent"/>
|
||||
<xacro:property name="forearm_roll" value="${sec_kinematics['forearm']['roll']}" scope="parent"/>
|
||||
<xacro:property name="forearm_pitch" value="${sec_kinematics['forearm']['pitch']}" scope="parent"/>
|
||||
<xacro:property name="forearm_yaw" value="${sec_kinematics['forearm']['yaw']}" scope="parent"/>
|
||||
|
||||
<xacro:property name="wrist_1_x" value="${sec_kinematics['wrist_1']['x']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_y" value="${sec_kinematics['wrist_1']['y']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_z" value="${sec_kinematics['wrist_1']['z']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_roll" value="${sec_kinematics['wrist_1']['roll']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_pitch" value="${sec_kinematics['wrist_1']['pitch']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_yaw" value="${sec_kinematics['wrist_1']['yaw']}" scope="parent"/>
|
||||
|
||||
<xacro:property name="wrist_2_x" value="${sec_kinematics['wrist_2']['x']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_y" value="${sec_kinematics['wrist_2']['y']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_z" value="${sec_kinematics['wrist_2']['z']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_roll" value="${sec_kinematics['wrist_2']['roll']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_pitch" value="${sec_kinematics['wrist_2']['pitch']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_yaw" value="${sec_kinematics['wrist_2']['yaw']}" scope="parent"/>
|
||||
|
||||
<xacro:property name="wrist_3_x" value="${sec_kinematics['wrist_3']['x']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_y" value="${sec_kinematics['wrist_3']['y']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_z" value="${sec_kinematics['wrist_3']['z']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_roll" value="${sec_kinematics['wrist_3']['roll']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_pitch" value="${sec_kinematics['wrist_3']['pitch']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_yaw" value="${sec_kinematics['wrist_3']['yaw']}" scope="parent"/>
|
||||
|
||||
<!-- INERTIA PARAMETERS -->
|
||||
<!-- mass -->
|
||||
<xacro:property name="base_mass" value="${sec_inertia_parameters['base_mass']}" scope="parent"/>
|
||||
<xacro:property name="shoulder_mass" value="${sec_inertia_parameters['shoulder_mass']}" scope="parent"/>
|
||||
<xacro:property name="upperarm_mass" value="${sec_inertia_parameters['upperarm_mass']}" scope="parent"/>
|
||||
<xacro:property name="forearm_mass" value="${sec_inertia_parameters['forearm_mass']}" scope="parent"/>
|
||||
<xacro:property name="wrist_1_mass" value="${sec_inertia_parameters['wrist_1_mass']}" scope="parent"/>
|
||||
<xacro:property name="wrist_2_mass" value="${sec_inertia_parameters['wrist_2_mass']}" scope="parent"/>
|
||||
<xacro:property name="wrist_3_mass" value="${sec_inertia_parameters['wrist_3_mass']}" scope="parent"/>
|
||||
|
||||
<!-- center of mass -->
|
||||
<xacro:property name="prop_base_cog" value="${sec_inertia_parameters['center_of_mass']['base_cog']}" scope="parent"/>
|
||||
<xacro:property name="prop_shoulder_cog" value="${sec_inertia_parameters['center_of_mass']['shoulder_cog']}" scope="parent"/>
|
||||
<xacro:property name="prop_upperarm_cog" value="${sec_inertia_parameters['center_of_mass']['upperarm_cog']}" scope="parent"/>
|
||||
<xacro:property name="prop_forearm_cog" value="${sec_inertia_parameters['center_of_mass']['forearm_cog']}" scope="parent"/>
|
||||
<xacro:property name="prop_wrist_1_cog" value="${sec_inertia_parameters['center_of_mass']['wrist_1_cog']}" scope="parent"/>
|
||||
<xacro:property name="prop_wrist_2_cog" value="${sec_inertia_parameters['center_of_mass']['wrist_2_cog']}" scope="parent"/>
|
||||
<xacro:property name="prop_wrist_3_cog" value="${sec_inertia_parameters['center_of_mass']['wrist_3_cog']}" scope="parent"/>
|
||||
|
||||
<!-- inertia -->
|
||||
<xacro:property name="prop_base_inertia" value="${sec_inertia_parameters['inertia']['base']}" scope="parent"/>
|
||||
<xacro:property name="prop_shoulder_inertia" value="${sec_inertia_parameters['inertia']['shoulder']}" scope="parent"/>
|
||||
<xacro:property name="prop_upperarm_inertia" value="${sec_inertia_parameters['inertia']['upperarm']}" scope="parent"/>
|
||||
<xacro:property name="prop_forearm_inertia" value="${sec_inertia_parameters['inertia']['forearm']}" scope="parent"/>
|
||||
<xacro:property name="prop_wrist_1_inertia" value="${sec_inertia_parameters['inertia']['wrist_1']}" scope="parent"/>
|
||||
<xacro:property name="prop_wrist_2_inertia" value="${sec_inertia_parameters['inertia']['wrist_2']}" scope="parent"/>
|
||||
<xacro:property name="prop_wrist_3_inertia" value="${sec_inertia_parameters['inertia']['wrist_3']}" scope="parent"/>
|
||||
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
@@ -0,0 +1,73 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://wiki.ros.org/xacro">
|
||||
<!--
|
||||
NOTE the macro defined in this file is NOT part of the public API of this
|
||||
package. Users CANNOT rely on this file being available, or stored in
|
||||
this location. Nor can they rely on the existence of the macro.
|
||||
-->
|
||||
|
||||
<xacro:macro name="cs_arm_transmission" params="prefix hw_interface">
|
||||
|
||||
<transmission name="${prefix}shoulder_pan_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}shoulder_pan_joint">
|
||||
<hardwareInterface>${hw_interface}</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}shoulder_pan_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${prefix}shoulder_lift_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}shoulder_lift_joint">
|
||||
<hardwareInterface>${hw_interface}</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}shoulder_lift_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${prefix}elbow_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}elbow_joint">
|
||||
<hardwareInterface>${hw_interface}</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}elbow_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${prefix}wrist_1_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}wrist_1_joint">
|
||||
<hardwareInterface>${hw_interface}</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}wrist_1_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${prefix}wrist_2_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}wrist_2_joint">
|
||||
<hardwareInterface>${hw_interface}</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}wrist_2_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${prefix}wrist_3_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="${prefix}wrist_3_joint">
|
||||
<hardwareInterface>${hw_interface}</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="${prefix}wrist_3_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user