ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Gazebo ROS Collision Detection

asked 2016-07-21 12:34:15 -0500

justinkgoh gravatar image

updated 2016-07-22 08:17:53 -0500

Hello all,

I am trying to get a topic with the collision by using the gazebo-ros-bumper plugin, but all of the resources I have found online have not worked for me.

Here is my xacro code for the robot arm.

<!-- ***************Robot Arms*************** -->
<xacro:include filename="$(find robsim_description)/urdf/kuka.xacro" />

<!-- ***************Robot Hands*************** -->
<xacro:include filename="$(find robsim_description)/urdf/sdhhand.xacro" />

<!-- ***************Joint*************** -->
<xacro:rev_joint_block parent="arm_extension" child="sdh_gehaeuse" xyz="0 0 0.0411" rpy="0 0 0" lower="0" upper="0"/>

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

Here is the code for my kuka arm:

<xacro:macro name="link_block" params="link xyz rpy filename material">
    <link name="${link}">
        <visual>
            <origin xyz="${xyz}" rpy="${rpy}"/>
            <geometry>
                <mesh filename="package://robsim_description/models/${filename}"/>
            </geometry>
        </visual>

        <collision>
            <origin xyz="${xyz}" rpy="${rpy}"/>
            <geometry>
                <mesh filename="package://robsim_description/models/${filename}"/>
            </geometry>
        </collision>

        <inertial>
            <mass value="1"/>
            <inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
        </inertial>
    </link>

    <gazebo reference="${link}">
        <turnGravityOff>true</turnGravityOff>
        <material>Gazebo/${material}</material>
    </gazebo>
</xacro:macro>

<xacro:macro name="rev_joint_block" params="parent child xyz rpy lower upper">
    <joint name="${parent}_${child}_joint" type="revolute">
        <parent link="${parent}"/>
        <child link="${child}"/>
        <origin xyz="${xyz}" rpy="${rpy}"/>
        <axis xyz="0 0 1" rpy="0 0 0"/>
        <limit lower="${lower}" upper="${upper}" effort="300.0" velocity="1000.0"/>
        <joint_properties damping="0.0" friction="0.0"/>
    </joint>
</xacro:macro>

<xacro:macro name="transmission_block" params="parent child">
  <transmission name="${parent}_${child}_trans">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="${parent}_${child}_joint">
            <hardwareInterface>PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="${parent}_${child}_motor">
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
</xacro:macro>

<!-- ***************Kuka Base Plate*************** -->
<xacro:link_block link="base_link" xyz="0 0 0.016" rpy="0 0 0" filename="kuka_base_plate.dae" material="Grey"/>

<!-- ***************Kuka A1 Joint***************** -->
<xacro:link_block link="a1" xyz="0 0 0.016" rpy="0 0 0" filename="a1.dae" material="Orange"/>
<joint name="base_a1" type="fixed">
    <parent link="base_link"/>
    <child link="a1"/>
</joint>

<!-- ***************Kuka A2 Joint**************** -->
<xacro:link_block link="a2" xyz="0 0 0" rpy="0 0 0" filename="a2.dae" material="Orange"/>
<xacro:rev_joint_block parent="a1" child="a2" xyz="0 0 0.3265" rpy="0 0 0" lower="-2.96706" upper="2.96706"/>
<xacro:transmission_block parent="a1" child="a2"/>

<!-- ***************Kuka E1 Joint**************** -->
<xacro:link_block link="e1" xyz="0 0 0" rpy="0 0 0" filename="e1.dae" material="Orange"/>
<xacro:rev_joint_block parent="a2" child="e1" xyz="0 0 0" rpy="1.5707 3.14159 0" lower="0" upper="3.14159"/>
<xacro:transmission_block parent="a2" child="e1"/>

<!-- ***************Kuka A3 Joint**************** -->
<xacro:link_block link="a3" xyz="0 0 0" rpy="0 0 0" filename="a3.dae" material="Orange"/>
<xacro:rev_joint_block parent="e1" child="a3" xyz="-0.4 0 0" rpy="-1.5707 0 1.5707" lower="-2.0944" upper="2.0944"/>
<xacro:transmission_block parent="e1" child="a3"/>

<!-- ***************Kuka A4 Joint**************** -->
<xacro:link_block link="a4" xyz="0 0 0" rpy="0 0 0" filename="a4.dae" material="Orange"/>
<xacro:rev_joint_block parent ...
(more)
edit retag flag offensive close merge delete

Comments

Where is your bumper plugin defined? And I'm also trying bumper simulation now and found the wiki might not be accurate. I'll edit it once I confirm the right way.

130s gravatar image 130s  ( 2016-07-21 17:37:14 -0500 )edit

I have tried it in several places. Including the one you suggested in the gazebo wiki site. The other ones I have tried are from here and here.

justinkgoh gravatar image justinkgoh  ( 2016-07-22 08:16:41 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-08-30 12:02:45 -0500

Mav16 gravatar image

Which link do you want to create a bumper on? You need to create a contact sensor first. I had a hard time getting this to run as well. I've attached some example code which you can edit as necessary. This code is in my atlas.gazebo file

<gazebo reference="your_link">
<!-- contact sensor -->
<sensor type="contact" name="your_link_contact_sensor">
  <update_rate>1000.0</update_rate>
  <always_on>1</always_on>
  <contact>
    <collision>bumper_collision</collision>
    <topic>/bumper_contact</topic>
  </contact>
<plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>1000.0</updateRate>
        <bumperTopicName>/robot_bumper</bumperTopicName>
        <frameName>world</frameName>
</plugin>
</sensor>

</gazebo>

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-07-21 12:34:15 -0500

Seen: 4,130 times

Last updated: Jul 22 '16