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 libgazebo_ros_bumper.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 ...