Skip to content

Commit

Permalink
Merge pull request #19 from Tiryoh/hotfix
Browse files Browse the repository at this point in the history
Fix old version xacro files
  • Loading branch information
Tiryoh authored Jun 8, 2018
2 parents 575fb3a + 150119e commit 290eb57
Show file tree
Hide file tree
Showing 4 changed files with 165 additions and 4 deletions.
80 changes: 80 additions & 0 deletions raspimouse_description/robots/raspimouse.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
<?xml version="1.0"?>
<robot name="raspimouse_on_gazebo"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:include filename="$(find raspimouse_description)/urdf/body/body.urdf.xacro"/>
<xacro:include filename="$(find raspimouse_description)/urdf/wheel/wheel.urdf.xacro"/>
<xacro:include filename="$(find raspimouse_description)/urdf/sensors/lightsens.urdf.xacro"/>

<!-- =============== Link & Joint =============== -->
<!-- Base -->
<link name="base_footprint"/>

<xacro:base parent="base_footprint">
<origin xyz="0 0 0.00185"/>
</xacro:base>

<!-- Wheel -->
<xacro:wheel prefix="right" parent="base_link">
<origin xyz="0 -0.0425 0.02215" rpy="1.57 0 0"/>
<axis xyz="0 0 -1"/>
</xacro:wheel>
<xacro:wheel prefix="left" parent="base_link">
<origin xyz="0 0.0425 0.02215" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</xacro:wheel>

<!-- Sensors -->
<xacro:light_sensor prefix="rf" parent="base_link">
<origin xyz="0.04 -0.045 0.032" rpy="0 0 0"/>
</xacro:light_sensor>

<xacro:light_sensor prefix="rs" parent="base_link">
<origin xyz="0.059 -0.01 0.032" rpy="0 0 -1.04"/>
</xacro:light_sensor>

<xacro:light_sensor prefix="ls" parent="base_link">
<origin xyz="0.059 0.01 0.032" rpy="0 0 1.04"/>
</xacro:light_sensor>

<xacro:light_sensor prefix="lf" parent="base_link">
<origin xyz="0.04 0.045 0.032" rpy="0 0 0"/>
</xacro:light_sensor>

<!-- =============== Transmission =============== -->
<!-- PositionJointInterface: requires position -->
<!-- <xacro:wheel_trans prefix="right" interface="PositionJointInterface"/> -->
<!-- <xacro:wheel_trans prefix="left" interface="PositionJointInterface"/> -->
<!-- VelocityJointInterface: requires position, velocity -->
<!-- for DiffDriveController -->
<xacro:wheel_trans prefix="right" interface="hardware_interface/VelocityJointInterface"/>
<xacro:wheel_trans prefix="left" interface="hardware_interface/VelocityJointInterface"/>
<!-- EffortJointInterface: requires position, velocity, effort -->
<!-- <xacro:wheel_trans prefix="right" interface="EffortJointInterface"/> -->
<!-- <xacro:wheel_trans prefix="left" interface="EffortJointInterface"/> -->

<!-- =============== Gazebo =============== -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>raspimouse_on_gazebo</robotNamespace>
</plugin>
</gazebo>

<!-- Base -->
<xacro:base_gazebo/>

<!-- Wheel -->
<xacro:wheel_gazebo prefix="right"/>
<xacro:wheel_gazebo prefix="left"/>

<!-- Sensors -->
<xacro:lightsensor_gazebo prefix="rf" base_rad="0" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lightsensor_gazebo prefix="rs" base_rad="-1.04" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lightsensor_gazebo prefix="ls" base_rad="1.04" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lightsensor_gazebo prefix="lf" base_rad="0" rad_range="0.3" min_range="0.01" max_range="0.6"/>

<raspimouse_on_gazebo/>
</robot>
81 changes: 81 additions & 0 deletions raspimouse_description/robots/raspimouse_urg.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
<?xml version="1.0"?>
<robot name="raspimouse_on_gazebo"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:include filename="$(find raspimouse_description)/urdf/body/body_urg.urdf.xacro"/>
<xacro:include filename="$(find raspimouse_description)/urdf/wheel/wheel.urdf.xacro"/>
<xacro:include filename="$(find raspimouse_description)/urdf/sensors/lightsens.urdf.xacro"/>
<xacro:include filename="$(find raspimouse_description)/urdf/sensors/lrf.urdf.xacro"/>

<!-- =============== Link & Joint =============== -->
<!-- Base -->
<link name="base_footprint"/>

<xacro:base parent="base_footprint">
<origin xyz="0 0 0.00185"/>
</xacro:base>

<!-- Wheel -->
<xacro:wheel prefix="right" parent="base_link">
<origin xyz="0 -0.0425 0.02215" rpy="1.57 0 0"/>
<axis xyz="0 0 -1"/>
</xacro:wheel>
<xacro:wheel prefix="left" parent="base_link">
<origin xyz="0 0.0425 0.02215" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</xacro:wheel>

<!-- Sensors -->
<xacro:light_sensor prefix="rf" parent="base_link">
<origin xyz="0.04 -0.045 0.032" rpy="0 0 0"/>
</xacro:light_sensor>

<xacro:light_sensor prefix="rs" parent="base_link">
<origin xyz="0.059 -0.01 0.032" rpy="0 0 -1.04"/>
</xacro:light_sensor>

<xacro:light_sensor prefix="ls" parent="base_link">
<origin xyz="0.059 0.01 0.032" rpy="0 0 1.04"/>
</xacro:light_sensor>

<xacro:light_sensor prefix="lf" parent="base_link">
<origin xyz="0.04 0.045 0.032" rpy="0 0 0"/>
</xacro:light_sensor>

<xacro:lrf_sensor prefix="urg_lrf_link" parent="base_link">
<origin xyz="0.0 0.0 0.14060" rpy="0 0 0"/>
<!-- <origin xyz="0.0 0.0 0.18745" rpy="0 0 0"/> -->
</xacro:lrf_sensor>

<!-- =============== Transmission =============== -->
<!-- <xacro:wheel_trans prefix="right" interface="EffortJointInterface"/> -->
<!-- <xacro:wheel_trans prefix="left" interface="EffortJointInterface"/> -->
<xacro:wheel_trans prefix="right" interface="hardware_interface/VelocityJointInterface"/>
<xacro:wheel_trans prefix="left" interface="hardware_interface/VelocityJointInterface"/>

<!-- =============== Gazebo =============== -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>raspimouse_on_gazebo</robotNamespace>
</plugin>
</gazebo>

<!-- Base -->
<xacro:base_gazebo/>

<!-- Wheel -->
<xacro:wheel_gazebo prefix="right"/>
<xacro:wheel_gazebo prefix="left"/>

<!-- Sensors -->
<xacro:lightsensor_gazebo prefix="rf" base_rad="0" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lightsensor_gazebo prefix="rs" base_rad="-1.04" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lightsensor_gazebo prefix="ls" base_rad="1.04" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lightsensor_gazebo prefix="lf" base_rad="0" rad_range="0.3" min_range="0.01" max_range="0.6"/>
<xacro:lrf_gazebo prefix="urg" base_rad="0" rad_range="4.71" min_range="0.10" max_range="5.6"/>

<raspimouse_on_gazebo/>
</robot>
4 changes: 2 additions & 2 deletions raspimouse_description/urdf/raspimouse.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@
<!-- <xacro:wheel_trans prefix="left" interface="PositionJointInterface"/> -->
<!-- VelocityJointInterface: requires position, velocity -->
<!-- for DiffDriveController -->
<xacro:wheel_trans prefix="right" interface="VelocityJointInterface"/>
<xacro:wheel_trans prefix="left" interface="VelocityJointInterface"/>
<xacro:wheel_trans prefix="right" interface="hardware_interface/VelocityJointInterface"/>
<xacro:wheel_trans prefix="left" interface="hardware_interface/VelocityJointInterface"/>
<!-- EffortJointInterface: requires position, velocity, effort -->
<!-- <xacro:wheel_trans prefix="right" interface="EffortJointInterface"/> -->
<!-- <xacro:wheel_trans prefix="left" interface="EffortJointInterface"/> -->
Expand Down
4 changes: 2 additions & 2 deletions raspimouse_description/urdf/raspimouse_urg.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,8 @@
<!-- =============== Transmission =============== -->
<!-- <xacro:wheel_trans prefix="right" interface="EffortJointInterface"/> -->
<!-- <xacro:wheel_trans prefix="left" interface="EffortJointInterface"/> -->
<xacro:wheel_trans prefix="right" interface="VelocityJointInterface"/>
<xacro:wheel_trans prefix="left" interface="VelocityJointInterface"/>
<xacro:wheel_trans prefix="right" interface="hardware_interface/VelocityJointInterface"/>
<xacro:wheel_trans prefix="left" interface="hardware_interface/VelocityJointInterface"/>

<!-- =============== Gazebo =============== -->
<gazebo>
Expand Down

0 comments on commit 290eb57

Please sign in to comment.