Fixed joint vs Continuous joint
I'm using Gazebo 9.7.0.
I'm adding a bumper sensor to my robot, and it appears different in Gazebo editor.
When the joint to the chassis is fixed:
It seems that the gripper, the yellow box, it is part of the chassis, the blue rectangle.
And, when the joint is continuous:
The gripper appears as a link in the editor.
Which is the best type of joint to a contact sensor?
Maybe, it would be better to set the sensor in the chassis.
And also, if I add a libgazeborosbumper.so plugin, the topic appears as part of the chassis if the joint is fixed:
/gazebo/odom_world/mybot/base_link/bumper_contact_sensor
The joint is named sensor_joint
, and the SDF generated from an URDF Xacro file is:
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from nav_odom_description/urdf/mybot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="mybot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- If a <gazebo> element is used without a reference="" property, it is
assumed the <gazebo> element is for the whole robot model. -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/mybot</robotNamespace>
</plugin>
</gazebo>
<gazebo reference="chassis">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="caster_wheel">
<preserveFixedJoint>true</preserveFixedJoint>
<mu1>0.0</mu1>
<!-- Equals to zero to remove the friction. -->
<mu2>0.0</mu2>
<!-- Equals to zero to remove the friction. -->
<material>Gazebo/Red</material>
</gazebo>
<!-- BUMPER -->
<gazebo reference="gripper">
<preserveFixedJoint>true</preserveFixedJoint>
<material>Gazebo/Yellow</material>
<sensor name="bumper_contact_sensor" type="contact">
<always_on>true</always_on>
<update_rate>30.0</update_rate>
<contact>
<collision>gripper_collision_collision</collision>
</contact>
<plugin filename="libgazebo_ros_bumper.so" name="gripper_bumper">
<bumperTopicName>gripper_contact_sensor_state</bumperTopicName>
<frameName>gripper</frameName>
</plugin>
</sensor>
</gazebo>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<!-- CYLINDER INERTIA -->
<!-- BOX INERTIA -->
<!-- SPHERE INERTIA -->
<!-- WHEEL MACRO -->
<link name="base_link"/>
<joint name="base_joint" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
</joint>
<!-- CHASSIS -->
<link name="chassis">
<collision>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<geometry>
<box size="0.4 0.2 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<geometry>
<box size="0.4 0.2 0.1"/>
</geometry>
<material name="orange"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<mass value="50.0"/>
<inertia ixx="0.208333333333" ixy="0" ixz="0" iyy="0.708333333333" iyz="0" izz="0.708333333333"/>
</inertial>
</link>
<!-- CASTER WHEEL -->
<joint name="caster_joint" type="fixed">
<parent link="chassis"/>
<child link="caster_wheel"/>
</joint>
<link name="caster_wheel">
<collision>
<origin rpy="0 0 0" xyz="-0.15 0 0.05"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="-0.15 0 0.05"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="-0.15 0 0.05"/>
<mass value="5"/>
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
</inertial>
</link>
<!-- BUMPER SENSOR -->
<joint name="sensor_joint" type="fixed">
<parent link="chassis"/>
<child link="gripper"/>
</joint>
<link name="gripper">
<collision name="gripper_collision">
<origin rpy="0 0 0" xyz="0.2 0 0.2"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0.225 0 0.1"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<mass value="0.1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="4.16666666667e-05" ixy="0" ixz="0" iyy="4.16666666667e-05" iyz="0" izz="4.16666666667e-05"/>
</inertial>
</link>
<link name="left_wheel">
<collision>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
<inertial>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<mass value="5"/>
<inertia ixx="0.0135416666667" ixy="0" ixz="0" iyy="0.0135416666667" iyz="0" izz="0.025"/>
</inertial>
</link>
<gazebo reference="left_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<joint name="left_wheel_hinge" type="continuous">
<parent link="chassis"/>
<child link="left_wheel"/>
<origin rpy="0 0 0" xyz="0.0 0.125 0.1"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="left_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_wheel_hinge">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="leftMotor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>10</mechanicalReduction>
</actuator>
</transmission>
<link name="right_wheel">
<collision>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
<inertial>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<mass value="5"/>
<inertia ixx="0.0135416666667" ixy="0" ixz="0" iyy="0.0135416666667" iyz="0" izz="0.025"/>
</inertial>
</link>
<gazebo reference="right_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<joint name="right_wheel_hinge" type="continuous">
<parent link="chassis"/>
<child link="right_wheel"/>
<origin rpy="0 0 0" xyz="0.0 -0.125 0.1"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="right_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_wheel_hinge">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rightMotor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>10</mechanicalReduction>
</actuator>
</transmission>
</robot>
Asked by VansFannel on 2019-04-01 13:07:43 UTC
Answers
I suspect you're using URDF to describe your robot, as opposed to SDF, correct?
Gazebo automatically lumps URDF fixed joints when converting it to SDF. You can prevent that by adding the following to your URDF:
<gazebo reference='joint_name'>
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>
Which is the best type of joint to a contact sensor?
I think it boils down to personal preference, both ways should work.
Asked by chapulina on 2019-04-01 15:01:08 UTC
Comments
Thanks for your answer. I've added your suggestion but I'm still have the same result. The gripper
link doesn't appears on Gazebo Editor. I have added the SDF generated to my question.
Asked by VansFannel on 2019-04-02 02:20:09 UTC
Hello, maybe it is too late now, but when you define a "fixed" joint, Gazebo will make both links together, removing the child from the list of links. This answer describes this behavior a litter better.
Asked by schulze_18 on 2019-11-09 07:51:50 UTC
Comments