URDF Link Port¶
Within a Gazebo Plugin GenericDomainModel, a URDF Link Port is represented by a GenericDomainModelPort with the following Attributes.
| Attributes | Value | Description |
|---|---|---|
| Type | urdf_link | |
| Attribute 7 | ros |
A URDF Link Port allows a designer to connect a Gazebo Plugin Model with a Component (which may be the parent of the Gazebo Plugin Model) that contains a physical model (generally a CAD Model).
If the CyPhy Master Interpreter is run, then the URDF Link GenericDomainModelPort’s name and the associated Physical Model’s link name in the generated URDF will used as a key and value respectively to populate the Gazebo Plugin GenericDomainModel’s connected template file Resource.
Example URDF Link GenericDomainModelPort
Example Template Resource
<robot>
<joint name="${base_link_name}_to_scan" type="fixed">
<parent link="${base_link_name}"/>
<child link="${base_link_name}_scan"/>
<origin rpy="0 0 0" xyz="0 0 0.03075"/>
</joint>
<link name="${base_link_name}_scan"/>
<gazebo reference="${base_link_name}_scan">
<sensor type="gpu_ray" name="${base_link_name}_scan">
...
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>${scan}</topicName>
<frameName>${base_link_name}_scan</frameName>
</plugin>
</sensor>
</gazebo>
</robot>
Example Generated URDF
<robot>
<joint name="rplidar_a2_0_to_scan" type="fixed">
<parent link="rplidar_a2_0"/>
<child link="rplidar_a2_0_scan"/>
<origin rpy="0 0 0" xyz="0 0 0.03075"/>
</joint>
<link name="rplidar_a2_0_scan"/>
<gazebo reference="rplidar_a2_0_scan">
<sensor type="gpu_ray" name="rplidar_a2_0_scan">
...
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>laserscan_1</topicName>
<frameName>rplidar_a2_0_scan</frameName>
</plugin>
</sensor>
</gazebo>
</robot>