Commit e46ba9a9 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Split the base into two separate meshes (base and fence) to allow proper coloring.

parent 15e6878d
......@@ -3,17 +3,11 @@
<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="obstacle_base" params="name">
<!-- IR distance sensors -->
<link name="${name}_link">
<inertial>
<mass value="50"/>
<origin xyz="1.01500000 1.26500000 0.04510729" rpy="0 0 0"/>
<inertia ixx="32.72577613" ixy="0.0" ixz="0.0" iyy="22.18978101" iyz="0.0" izz="53.20566219" />
</inertial>
<inertial>
<mass value="1"/>
<origin xyz="1.01500000 1.26500000 0.04510729" rpy="0 0 0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
<mass value="40"/>
<origin xyz="1.01500000 1.26500000 -0.015" rpy="0 0 0"/>
<inertia ixx="21.33933333" ixy="0.0" ixz="0.0" iyy="13.73933333" iyz="0.0" izz="35.07266667" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
......@@ -29,7 +23,49 @@
</collision>
</link>
<link name="${name}_fence_link">
<inertial>
<mass value="10"/>
<origin xyz="1.0100000 1.2600000 0.25" rpy="0 0 0"/>
<inertia ixx="10.12791445" ixy="0.0" ixz="0.0" iyy="7.31441888" iyz="0.0" izz="17.02566667" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://bioloid_description/meshes/ceabot/obstacle_fence.stl"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://bioloid_description/meshes/ceabot/obstacle_fence.stl"/>
</geometry>
</collision>
</link>
<joint name="j_base_fence" type="fixed">
<parent link="${name}_link"/>
<child link="${name}_fence_link"/>
<origin xyz="0.005 0.005 0" rpy="0 0 0" />
</joint>
<gazebo reference="${name}_link">
<material>Gazebo/Green</material>
<gravity>true</gravity>
<selfCollide>false</selfCollide>
<maxContacts>10</maxContacts>
<dampingFactor>0.2</dampingFactor>
<maxVel>0.01</maxVel>
<minDepth>0.0</minDepth>
<fdir1>0 0 0</fdir1>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<kp>1000000000.0</kp>
<kd>1.0</kd>
</gazebo>
<gazebo reference="${name}_fence_link">
<material>Gazebo/White</material>
<gravity>true</gravity>
<selfCollide>false</selfCollide>
<maxContacts>10</maxContacts>
......
......@@ -2,10 +2,10 @@
<sdf version="1.4">
<world name="default">
<physics type="ode">
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
<!-- <real_time_factor>0.1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>-->
<!-- <real_time_factor>1.0</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>-->
<real_time_factor>0.1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<max_step_size>0.001</max_step_size>
<gravity>0 0 -9.8</gravity>
<ode>
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment