openarm_ros2/openarm_bimanual_description/urdf/openarm_bimanual.urdf.xacro

63 lines
3.0 KiB
Plaintext
Raw Normal View History

<?xml version="1.0" ?>
<!--
 Copyright 2025 Reazon Holdings, Inc.
 Licensed under the Apache License, Version 2.0 (the "License");
 you may not use this file except in compliance with the License.
 You may obtain a copy of the License at
  http://www.apache.org/licenses/LICENSE-2.0
 Unless required by applicable law or agreed to in writing, software
 distributed under the License is distributed on an "AS IS" BASIS,
 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 See the License for the specific language governing permissions and
 limitations under the License.
-->
2025-03-11 04:06:46 +00:00
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:arg name="hardware_type" default="real" />
<!-- Robot description parameters -->
<xacro:arg name="prefix" default="" />
<!-- Control-related parameters -->
<xacro:arg name="right_can_device" default="can0" />
<xacro:arg name="left_can_device" default="can1" />
<xacro:arg name="hardware_type" default="real" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:include filename="$(find openarm_description)/urdf/openarm.robot.xacro"/>
<xacro:include filename="$(find openarm_bimanual_description)/urdf/openarm_pedestal.urdf"/>
<xacro:include filename="openarm_bimanual_sensors.xacro"/>
<link name="world"/>
<joint name="dummy_joint" type="fixed">
<parent link="world"/>
<child link="pedestal_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<xacro:openarm_robot prefix="right_" side="right" zero_pos="arm"/>
2025-04-01 04:47:32 +00:00
<joint name="right_fixed1" type="fixed">
<parent link="pedestal_link"/>
<child link="right_dummy_link"/>
2025-03-10 12:24:14 +00:00
<origin rpy="${3.0186531925068127 + pi} -1.5707963267948268 0.12293946108298068" xyz="-0.09 0.0 0.893"/>
</joint>
2025-04-15 06:38:11 +00:00
<xacro:openarm_robot prefix="left_" side="left" zero_pos="arm"/>
<joint name="left_fixed1" type="fixed">
<parent link="pedestal_link"/>
<child link="left_dummy_link"/>
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
</joint>
<!-- Include control configuration for both arms -->
<xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro"/>
<xacro:arg name="right_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:arg name="left_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="RightOpenArmHW" prefix="right_" initial_positions_file="$(arg right_initial_positions_file)" can_device="$(arg right_can_device)" hardware_type="$(arg hardware_type)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
<xacro:openarm_ros2_control name="LeftOpenArmHW" prefix="left_" initial_positions_file="$(arg left_initial_positions_file)" can_device="$(arg left_can_device)" hardware_type="$(arg hardware_type)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
</robot>