Created
May 16, 2019 07:38
-
-
Save tahsinkose/8f261de834ce9f48ae361c5ad066477a to your computer and use it in GitHub Desktop.
Gimbal URDF used in DJI M100 Gazebo Simulation.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | |
<xacro:macro name="dji_m100_gimbal"> | |
<joint name="virtual_gimbal_joint" type="fixed"> | |
<origin xyz="-0.1 0 -0.04" rpy="0 0 0"/> | |
<parent link="base_link"/> | |
<child link="virtual_gimbal_link"/> | |
</joint> | |
<gazebo reference="virtual_gimbal_joint"> | |
<preserveFixedJoint>true</preserveFixedJoint> | |
</gazebo> | |
<link name="virtual_gimbal_link"> | |
<inertial> | |
<mass value="0.0001" /> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" /> | |
</inertial> | |
<visual> | |
<geometry> | |
<box size="0.0001 0.0001 0.0001" /> | |
</geometry> | |
</visual> | |
<collision> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<geometry> | |
<mesh filename="package://dji_m100_description/meshes/dji_m100/gimbal.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<joint name="gimbal_roll_joint" type="continuous"> | |
<parent link="virtual_gimbal_link" /> | |
<child link="gimbal_roll_link" /> | |
<axis xyz="1 0 0" /> | |
<dynamics damping="0.0" friction="0.0" /> | |
</joint> | |
<link name="gimbal_roll_link"> | |
<inertial> | |
<mass value="0.0001" /> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" /> | |
</inertial> | |
<visual> | |
<geometry> | |
<box size="0.0001 0.0001 0.0001" /> | |
</geometry> | |
</visual> | |
</link> | |
<joint name="gimbal_pitch_joint" type="continuous"> | |
<parent link="gimbal_roll_link" /> | |
<child link="gimbal_pitch_link" /> | |
<axis xyz="0 1 0" /> | |
<dynamics damping="0.0" friction="0.0" /> | |
</joint> | |
<link name="gimbal_pitch_link"> | |
<inertial> | |
<mass value="0.0001" /> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" /> | |
</inertial> | |
<visual> | |
<geometry> | |
<box size="0.001 0.0001 0.0001" /> | |
</geometry> | |
</visual> | |
</link> | |
<joint name="gimbal_yaw_joint" type="continuous"> | |
<parent link="gimbal_pitch_link" /> | |
<child link="gimbal_yaw_link" /> | |
<axis xyz="0 0 1" /> | |
<dynamics damping="0.0" friction="0.0" /> | |
</joint> | |
<link name="gimbal_yaw_link"> | |
<inertial> | |
<mass value="0.0001" /> | |
<origin xyz="0 0 0" rpy="0 0 ${-M_PI}" /> | |
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" /> | |
</inertial> | |
<visual> | |
<origin xyz="0 0 0" rpy="0 0 ${-M_PI}" /> | |
<geometry> | |
<mesh filename="package://dji_m100_description/meshes/dji_m100/gimbal.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin xyz="0 0 0" rpy="0 0 ${-M_PI}" /> | |
<geometry> | |
<mesh filename="package://dji_m100_description/meshes/dji_m100/gimbal.stl"/> | |
</geometry> | |
</collision> | |
</link> | |
<joint name="camera_joint" type="continuous"> | |
<parent link="gimbal_yaw_link" /> | |
<child link="camera_link" /> | |
<axis xyz="0 0 1" /> | |
<dynamics damping="0.0" friction="0.0" /> | |
</joint> | |
<link name="camera_link"> | |
</link> | |
<joint name="camera_optical_joint" type="fixed"> | |
<origin xyz="0 0 0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" /> | |
<parent link="camera_link" /> | |
<child link="camera_optical_frame"/> | |
</joint> | |
<gazebo reference="camera_optical_joint"> | |
<preserveFixedJoint>true</preserveFixedJoint> | |
</gazebo> | |
<link name="camera_optical_frame"> | |
</link> | |
<gazebo reference="gimbal_yaw_link"> | |
<sensor type="camera" name="camera_camera_sensor"> | |
<update_rate>10</update_rate> | |
<camera> | |
<!-- <pose>0.027 0 -0.027 0 1.57 0</pose> --> | |
<!-- <pose>0.027 0 -0.027 0 1.57 0</pose> --> | |
<pose>0.107 0 -0.127 0 0 0</pose> | |
<horizontal_fov>${94 * M_PI/180.0}</horizontal_fov> | |
<image> | |
<format>R8G8B8</format> | |
<width>640</width> | |
<height>480</height> | |
</image> | |
<clip> | |
<near>0.01</near> | |
<far>100</far> | |
</clip> | |
</camera> | |
<plugin name="camera_controller" filename="libgazebo_ros_camera.so"> | |
<cameraName>camera</cameraName> | |
<alwaysOn>true</alwaysOn> | |
<updateRate>10</updateRate> | |
<imageTopicName>dji_sdk/image_raw</imageTopicName> | |
<cameraInfoTopicName>dji_sdk/camera_info</cameraInfoTopicName> | |
<frameName>camera_optical_frame</frameName> | |
</plugin> | |
</sensor> | |
</gazebo> | |
</xacro:macro> | |
</robot> | |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment