Adding sdf plugin in urdf
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.