Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix invalid "`" in URDF. #12

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
349 changes: 70 additions & 279 deletions robots/hsrb4s.obj.urdf

Large diffs are not rendered by default.

349 changes: 70 additions & 279 deletions robots/hsrb4s.urdf

Large diffs are not rendered by default.

6 changes: 3 additions & 3 deletions urdf/arm_v0/arm.transmission.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ POSSIBILITY OF SUCH DAMAGE.
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="hsrb_arm_transmission" params="prefix">
<hsrb_position_joint_transmission joint="${prefix}_lift_joint" reduction="1"/>
<hsrb_position_joint_transmission joint="${prefix}_flex_joint" reduction="1"/>
<hsrb_position_joint_transmission joint="${prefix}_roll_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_lift_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_flex_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_roll_joint" reduction="1"/>
</xacro:macro>

</robot>
2 changes: 1 addition & 1 deletion urdf/arm_v0/arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- arm -->
<xacro:macro name="hsrb_arm" params="prefix parent *origin">
<joint name="${prefix}_lift_joint" type="prismatic">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<axis xyz="0.0 0.0 1.0" />
<limit effort="100.0" velocity="0.2" lower="0.0" upper="0.69" />
<parent link="${parent}" />
Expand Down
6 changes: 3 additions & 3 deletions urdf/base_v2/base.transmission.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="hsrb_base_transmission" params="prefix">
<hsrb_velocity_joint_transmission joint="${prefix}_r_drive_wheel_joint" reduction="1"/>
<hsrb_velocity_joint_transmission joint="${prefix}_l_drive_wheel_joint" reduction="1"/>
<hsrb_position_joint_transmission joint="${prefix}_roll_joint" reduction="1"/>
<xacro:hsrb_velocity_joint_transmission joint="${prefix}_r_drive_wheel_joint" reduction="1"/>
<xacro:hsrb_velocity_joint_transmission joint="${prefix}_l_drive_wheel_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_roll_joint" reduction="1"/>
</xacro:macro>
</robot>
4 changes: 2 additions & 2 deletions urdf/base_v2/base.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- drive wheel -->
<xacro:macro name="hsrb_drive_wheel" params="prefix suffix parent *origin">
<joint name="${prefix}_${suffix}_drive_wheel_joint" type="continuous">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<axis xyz="0.0 1.0 0.0" />
<limit effort="${drive_wheel_max_effort}" velocity="${drive_wheel_max_velocity}" />
<parent link="${parent}" />
Expand Down Expand Up @@ -86,7 +86,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- passive wheel -->
<xacro:macro name="hsrb_passive_wheel" params="prefix suffix parent *origin">
<joint name="${prefix}_${suffix}_passive_wheel_x_frame_joint" type="continuous">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<axis xyz="1.0 0.0 0.0" />
<limit effort="1.0" velocity="3.0" />
<parent link="${parent}" />
Expand Down
36 changes: 18 additions & 18 deletions urdf/common.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ POSSIBILITY OF SUCH DAMAGE.

<xacro:property name="pi" value="3.14159265359"/>

<macro name="hsrb_position_joint_transmission" params="joint reduction">
<xacro:macro name="hsrb_position_joint_transmission" params="joint reduction">
<transmission name="${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
Expand All @@ -44,9 +44,9 @@ POSSIBILITY OF SUCH DAMAGE.
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
</macro>
</xacro:macro>

<macro name="hsrb_effort_joint_transmission" params="joint reduction">
<xacro:macro name="hsrb_effort_joint_transmission" params="joint reduction">
<transmission name="${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
Expand All @@ -57,9 +57,9 @@ POSSIBILITY OF SUCH DAMAGE.
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
</macro>
</xacro:macro>

<macro name="hsrb_velocity_joint_transmission" params="joint reduction">
<xacro:macro name="hsrb_velocity_joint_transmission" params="joint reduction">
<transmission name="${prefix}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
Expand All @@ -70,28 +70,28 @@ POSSIBILITY OF SUCH DAMAGE.
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
</macro>
</xacro:macro>

<macro name="gazebo_link" params="name gravity collide friction">
<xacro:macro name="gazebo_link" params="name gravity collide friction">
<gazebo reference="${name}">
<selfCollide>${collide}</selfCollide>
<gravity>${gravity}</gravity>
<mu1>${friction}</mu1>
<mu2>${friction}</mu2>
</gazebo>
</macro>
</xacro:macro>

<macro name="gazebo_link_flat_black" params="name gravity collide friction">
<xacro:macro name="gazebo_link_flat_black" params="name gravity collide friction">
<gazebo reference="${name}">
<selfCollide>${collide}</selfCollide>
<gravity>${gravity}</gravity>
<mu1>${friction}</mu1>
<mu2>${friction}</mu2>
<material value="Gazebo/FlatBlack"/>
</gazebo>
</macro>
</xacro:macro>

<macro name="gazebo_link_caster" params="name">
<xacro:macro name="gazebo_link_caster" params="name">
<gazebo reference="${name}">
<selfCollide>false</selfCollide>
<gravity>true</gravity>
Expand All @@ -100,9 +100,9 @@ POSSIBILITY OF SUCH DAMAGE.
<maxVel>1.0</maxVel>
<material value="Gazebo/FlatBlack"/>
</gazebo>
</macro>
</xacro:macro>

<macro name="gazebo_link_rubber" params="name">
<xacro:macro name="gazebo_link_rubber" params="name">
<gazebo reference="${name}">
<selfCollide>false</selfCollide>
<gravity>true</gravity>
Expand All @@ -116,19 +116,19 @@ POSSIBILITY OF SUCH DAMAGE.
<minDepth>0.00</minDepth>
<material value="Gazebo/FlatBlack"/>
</gazebo>
</macro>
</xacro:macro>

<macro name="gazebo_joint" params="name">
<xacro:macro name="gazebo_joint" params="name">
<gazebo reference="${name}">
<xacro:if value="$(arg implicit_damping)">
<implicitSpringDamper>1</implicitSpringDamper>
</xacro:if>
</gazebo>
</macro>
</xacro:macro>

<macro name="gazebo_joint_mimic" params="name">
<xacro:macro name="gazebo_joint_mimic" params="name">
<gazebo reference="${name}">
</gazebo>
</macro>
</xacro:macro>

</robot>
6 changes: 3 additions & 3 deletions urdf/hand_v0/hand.transmission.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://www.ros.org/wiki.xacro">
<xacro:macro name="hsrb_hand_transmission" params="prefix">
<hsrb_effort_joint_transmission joint="${prefix}_motor_joint" reduction="1"/>
<hsrb_effort_joint_transmission joint="${prefix}_l_spring_proximal_joint" reduction="1"/>
<hsrb_effort_joint_transmission joint="${prefix}_r_spring_proximal_joint" reduction="1"/>
<xacro:hsrb_effort_joint_transmission joint="${prefix}_motor_joint" reduction="1"/>
<xacro:hsrb_effort_joint_transmission joint="${prefix}_l_spring_proximal_joint" reduction="1"/>
<xacro:hsrb_effort_joint_transmission joint="${prefix}_r_spring_proximal_joint" reduction="1"/>
</xacro:macro>
</robot>
20 changes: 10 additions & 10 deletions urdf/hand_v0/hand.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- gripper base -->
<xacro:macro name="hsrb_gripper_base" params="prefix parent *origin">
<joint name="${prefix}_palm_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_palm_link" />
</joint>
Expand Down Expand Up @@ -112,7 +112,7 @@ POSSIBILITY OF SUCH DAMAGE.

<xacro:macro name="hsrb_hand" params="prefix parent *origin">
<xacro:hsrb_gripper_base prefix="${prefix}" parent="${parent}">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
</xacro:hsrb_gripper_base>

<xacro:hsrb_finger_with_vacuum prefix="${prefix}" suffix="l" parent="${prefix}_palm_link">
Expand All @@ -137,8 +137,8 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- gripper finger proximal base -->
<xacro:macro name="hsrb_finger_proximal_base" params="prefix suffix parent *origin *axis">
<joint name="${prefix}_${suffix}_proximal_joint" type="revolute">
<insert_block name="origin" />
<insert_block name="axis" />
<xacro:insert_block name="origin" />
<xacro:insert_block name="axis" />
<limit effort="100.0" velocity="1.0"
lower="${proximal_joint_angle_range_min}"
upper="${proximal_joint_angle_range_max}" />
Expand All @@ -152,7 +152,7 @@ POSSIBILITY OF SUCH DAMAGE.
<xacro:hsrb_gripper_dummy_link name="${prefix}_${suffix}_proximal_link" />

<joint name="${prefix}_${suffix}_spring_proximal_joint" type="revolute">
<insert_block name="axis" />
<xacro:insert_block name="axis" />
<limit effort="100.0" velocity="1.0"
lower="${spring_proximal_joint_angle_range_min}"
upper="${spring_proximal_joint_angle_range_max}" />
Expand All @@ -165,8 +165,8 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- gripper finger distal base -->
<xacro:macro name="hsrb_finger_distal_base" params="prefix suffix parent *origin *axis">
<joint name="${prefix}_${suffix}_mimic_distal_joint" type="revolute">
<insert_block name="origin" />
<insert_block name="axis" />
<xacro:insert_block name="origin" />
<xacro:insert_block name="axis" />
<limit effort="100.0" velocity="1.0"
lower="${-spring_proximal_joint_angle_range_max}"
upper="${-spring_proximal_joint_angle_range_min}" />
Expand All @@ -180,7 +180,7 @@ POSSIBILITY OF SUCH DAMAGE.
<xacro:hsrb_gripper_dummy_link name="${prefix}_${suffix}_mimic_distal_link" />

<joint name="${prefix}_${suffix}_distal_joint" type="revolute">
<insert_block name="axis" />
<xacro:insert_block name="axis" />
<limit effort="100.0" velocity="1.0"
lower="${-proximal_joint_angle_range_max}"
upper="${-proximal_joint_angle_range_min}" />
Expand All @@ -194,7 +194,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- finger with vacuum -->
<xacro:macro name="hsrb_finger_with_vacuum" params="prefix suffix parent *origin">
<xacro:hsrb_finger_proximal_base prefix="${prefix}" suffix="${suffix}" parent="${parent}">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<axis xyz="1.0 0.0 0.0" />
</xacro:hsrb_finger_proximal_base>

Expand Down Expand Up @@ -302,7 +302,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- finger without vacuum -->
<xacro:macro name="hsrb_finger_without_vacuum" params="prefix suffix parent *origin">
<xacro:hsrb_finger_proximal_base prefix="${prefix}" suffix="${suffix}" parent="${parent}">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<axis xyz="-1.0 0.0 0.0" />
</xacro:hsrb_finger_proximal_base>

Expand Down
4 changes: 2 additions & 2 deletions urdf/head_v2/head.transmission.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ POSSIBILITY OF SUCH DAMAGE.
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="hsrb_head_transmission" params="prefix">
<hsrb_position_joint_transmission joint="${prefix}_pan_joint" reduction="1"/>
<hsrb_position_joint_transmission joint="${prefix}_tilt_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_pan_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_tilt_joint" reduction="1"/>
</xacro:macro>

</robot>
2 changes: 1 addition & 1 deletion urdf/head_v2/head.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- head -->
<xacro:macro name="hsrb_head" params="prefix parent *origin">
<joint name="${prefix}_pan_joint" type="revolute">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<axis xyz="0.0 0.0 1.0" />
<limit effort="100.0" velocity="1.0" lower="-3.84" upper="1.75" />
<parent link="${parent}" />
Expand Down
2 changes: 1 addition & 1 deletion urdf/sensors/ft_sensor.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ POSSIBILITY OF SUCH DAMAGE.

<xacro:macro name="ft_sensor" params="prefix robot_namespace parent joint_name *origin">
<joint name="${prefix}_ft_sensor_frame_joint" type="fixed">
<insert_block name="origin"/>
<xacro:insert_block name="origin"/>
<parent link="${parent}"/>
<child link="${prefix}_ft_sensor_frame"/>
</joint>
Expand Down
2 changes: 1 addition & 1 deletion urdf/sensors/imu.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- imu sensor -->
<xacro:macro name="imu_sensor" params="prefix parent robot_namespace *origin">
<joint name="${prefix}_imu_frame_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_imu_frame" />
</joint>
Expand Down
2 changes: 1 addition & 1 deletion urdf/sensors/laser.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- range sensor -->
<xacro:macro name="laser" params="prefix robot_namespace parent *origin">
<joint name="${prefix}_range_sensor_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_range_sensor_link" />
</joint>
Expand Down
2 changes: 1 addition & 1 deletion urdf/sensors/rgb_sensor.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ POSSIBILITY OF SUCH DAMAGE.

<xacro:macro name="rgb_sensor" params="prefix parent robot_namespace *origin baseline">
<joint name="${prefix}_camera_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_camera_link" />
</joint>
Expand Down
4 changes: 2 additions & 2 deletions urdf/sensors/rgbd_sensor.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- rgbd_sensor -->
<xacro:macro name="rgbd_sensor" params="prefix parent robot_namespace sensor_name *origin">
<joint name="${prefix}_${sensor_name}_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}"/> <child link="${prefix}_${sensor_name}_link"/>
</joint>

Expand Down Expand Up @@ -68,7 +68,7 @@ POSSIBILITY OF SUCH DAMAGE.
<parent link="${prefix}_${sensor_name}_link"/>
<child link="${prefix}_${sensor_name}_gazebo_frame"/>
</joint>
`

<link name="${prefix}_${sensor_name}_gazebo_frame"></link>

<xacro:rgbd_sensor_gazebo
Expand Down
2 changes: 1 addition & 1 deletion urdf/sensors/wide_camera.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- wide rgb camera -->
<xacro:macro name="wide_camera" params="prefix parent robot_namespace rpy *origin">
<joint name="${prefix}_camera_frame_joint" type="fixed">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_camera_frame" />
</joint>
Expand Down
2 changes: 1 addition & 1 deletion urdf/torso_v0/torso.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ POSSIBILITY OF SUCH DAMAGE.
<!-- torso -->
<xacro:macro name="hsrb_torso" params="prefix parent mimic_joint *origin">
<joint name="${prefix}_lift_joint" type="prismatic">
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<!-- <origin xyz="0.0 0.0 0.752" rpy="0.0 0.0 0.0" /> -->
<axis xyz="0.0 0.0 1.0" />
<limit effort="100.0" velocity="0.1" lower="0.0" upper="0.345" />
Expand Down
4 changes: 2 additions & 2 deletions urdf/wrist_v0/wrist.transmission.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ POSSIBILITY OF SUCH DAMAGE.
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="hsrb_wrist_transmission" params="prefix">
<hsrb_position_joint_transmission joint="${prefix}_flex_joint" reduction="1"/>
<hsrb_position_joint_transmission joint="${prefix}_roll_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_flex_joint" reduction="1"/>
<xacro:hsrb_position_joint_transmission joint="${prefix}_roll_joint" reduction="1"/>
</xacro:macro>

</robot>