Gazebo | Ignition | Community
Ask Your Question
0

Adding sdf plugin in urdf

asked 2020-05-14 12:27:36 -0600

Hello, I would like to use a plugin, defined as a model in the sdf format, as a sensor on the endeffector of my robot arm defined in URDF.

I would like to do the same as the camera Gazebo plugin in my URDF:

<gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
    <update_rate>30.0</update_rate>
    <camera name="head">
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
        <width>800</width>
        <height>800</height>
        <format>R8G8B8</format>
        </image>
        <clip>
        <near>0.02</near>
        <far>300</far>
        </clip>
        <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.007</stddev>
        </noise>
    </camera>
    <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        <cameraName>camera</cameraName>
        <alwaysOn>true</alwaysOn>
        <updateRate>10</updateRate>
        <imageTopicName>rgb/image_raw</imageTopicName>
        <depthImageTopicName>depth/image_raw</depthImageTopicName>
        <pointCloudTopicName>depth/points</pointCloudTopicName>
        <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
        <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
        <frameName>camera_link</frameName>
        <baseline>0.1</baseline>
        <distortion_k1>0.0</distortion_k1>
        <distortion_k2>0.0</distortion_k2>
        <distortion_k3>0.0</distortion_k3>
        <distortion_t1>0.0</distortion_t1>
        <distortion_t2>0.0</distortion_t2>
        <pointCloudCutoff>0.4</pointCloudCutoff>
        <robotNamespace>/</robotNamespace>
    </plugin>
    </sensor>
</gazebo>

<link name="camera_link">
    <collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <box size="0.05 0.05 0.05"/>
        </geometry>
    </collision>
    <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <box size="0.05 0.05 0.05"/>
        </geometry>
        <material name="black"/>
    </visual>
    <inertial>
        <mass value="1e-5" />
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
    </inertial>
</link>

<joint name="camera_joint" type="fixed">
    <axis xyz="0 1 0" />
    <origin xyz="0 0 -0.025" rpy="1.57 1.57 0"/>
    <parent link="end_effector"/>
    <child link="camera_link"/>
</joint>

But I would like to use the following plugin, defined as a model in the sdf format, as a sensor in stead of a camera:

<model name="timepix">
  <static>1</static>
  <link name="link">
    <pose>0 1.0 0.0 0 0 0</pose>
    <visual name="visual">
      <geometry>
        <box>
          <size>0.2 0.2 0.2</size>
        </box>
      </geometry>
    </visual>
  </link>
  <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</model>

See with the SDF the plugin is defined in the SDF file of the world that I'm using but I would like to define it in the URDF to attach it on my endeffector. I can't seem to implement this since URDF links and joints don't support plugin tags. I tried switching the camera plugin with the timepix plugin but this doesn't work in the defined Gazebo plugin.

All help on how to do this would be much appreciated.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-05-18 05:06:49 -0600

kumpakri gravatar image

updated 2020-05-20 03:56:22 -0600

When I look into your code, the gazebo_timepix plugin seems like a Model plugin, because it is placed directly inside the model tags. Whereas the gazebo_ros_camera plugin is a Sensor plugin. It is placed inside the sensor tags.

If you wish to attach the gazebo_timepix plugin to the timepix model in timepix URDF description file you write:

<gazebo>
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

EDIT

There are various types of plugins (Model, Sensor, World, System, Visual) and those cannot be used the same way. The first thing you need to figure out is what type of plugin the timepix plugin is.

If it is the Model plugin, you can only use it by writing the lines shown below inside your URDF description of the robot you are attaching it to.

<gazebo>
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

This plugin gets pointer to the model and the sdf parameters you can specify inside the plugin description.

Load function for model plugin:

void MyModelPlugin::Load( physics::ModelPtr _parent,
                                sdf::ElementPtr _sdf)
    {...}

If it is some sensor plugin, you can only attach it to a sensor of appropriate type. So only if the Load function of this plugin look something like the code shown below, you can directly switch the plugin for the camera controller plugin in your example.

void MyCameraPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
    {
        ...
        CameraPlugin::Load(_parent,_sdf);
        ...
    }

You would write

<gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
    <update_rate>30.0</update_rate>
    <camera name="head">
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
        <width>800</width>
        <height>800</height>
        <format>R8G8B8</format>
        </image>
        <clip>
        <near>0.02</near>
        <far>300</far>
        </clip>
        <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.007</stddev>
        </noise>
    </camera>
    <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
    </sensor>
</gazebo>

If the plugin works attached to model like

<model name="timepix">
  <static>1</static>
  <link name="link">
    <pose>0 1.0 0.0 0 0 0</pose>
    <visual name="visual">
      <geometry>
        <box>
          <size>0.2 0.2 0.2</size>
        </box>
      </geometry>
    </visual>
  </link>
  <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</model>

It is a Model plugin and you have to use it as one. The 'camera_link' must be a part of some model. So the timepix model plugin would go inside the description of this model.

edit flag offensive delete link more

Comments

Thank you for you answer. However, I don't want to define the reference for the plugin to a model in the SDF. In other words, I won't use the model timepix. This model was provided by the package in a SDF file and I will not use this. I want to reference the plugin to a link (camera_link) defined in the URDF so that I can control the manipulator with the sensor attached to it.

student_Ros_melodic_mobile_manipulator gravatar imagestudent_Ros_melodic_mobile_manipulator ( 2020-05-19 07:42:43 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2020-05-14 12:27:36 -0600

Seen: 834 times

Last updated: May 20 '20