-
Notifications
You must be signed in to change notification settings - Fork 67
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
* Add x500_gimbal model * Delete models/x500_gimbal/LICENSE The license is not necessary since the model is included in the SDF
- Loading branch information
1 parent
4ddfc13
commit 36f49cb
Showing
6 changed files
with
392 additions
and
0 deletions.
There are no files selected for viewing
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
<?xml version="1.0"?> | ||
<model> | ||
<name>x500_gimbal</name> | ||
<version>1.0</version> | ||
<sdf version="1.9">model.sdf</sdf> | ||
<author> | ||
<name>Stefano Colli</name> | ||
<email>[email protected]</email> | ||
</author> | ||
<description>Model of the X500 with a camera attached on a gimbal.</description> | ||
</model> |
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,381 @@ | ||
<?xml version="1.0" encoding="UTF-8"?> | ||
<sdf version='1.9'> | ||
<model name='x500_gimbal'> | ||
<include merge='true'> | ||
<uri>x500</uri> | ||
</include> | ||
|
||
<!-- Gimbal mount point --> | ||
<link name="cgo3_mount_link"> | ||
<inertial> | ||
<pose>0 0 0.18 0 0 0</pose> | ||
<mass>0.1</mass> | ||
<inertia> | ||
<ixx>0.001</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>0.001</iyy> | ||
<iyz>0</iyz> | ||
<izz>0.001</izz> | ||
</inertia> | ||
</inertial> | ||
<visual name="cgo3_mount_visual"> | ||
<pose>0.03 0 0.262 0 0 0</pose> | ||
<geometry> | ||
<mesh> | ||
<scale>0.001 0.001 0.001</scale> | ||
<uri>model://x500_gimbal/meshes/cgo3_mount_remeshed_v1.stl</uri> | ||
</mesh> | ||
</geometry> | ||
<material> | ||
<ambient>.175 .175 .175 1.0</ambient> | ||
<diffuse>.175 .175 .175 1.0</diffuse> | ||
<specular>.175 .175 .175 1.0</specular> | ||
</material> | ||
</visual> | ||
</link> | ||
<joint name="cgo3_mount_joint" type='revolute'> | ||
<child>cgo3_mount_link</child> | ||
<parent>base_link</parent> | ||
<pose>0 0 0 0 0 0</pose> | ||
<axis> | ||
<xyz>0 0 1</xyz> | ||
<limit> | ||
<lower>0</lower> | ||
<upper>0</upper> | ||
<effort>100</effort> | ||
<velocity>-1</velocity> | ||
</limit> | ||
<dynamics> | ||
<damping>1</damping> | ||
</dynamics> | ||
</axis> | ||
<physics> | ||
<ode> | ||
<implicit_spring_damper>1</implicit_spring_damper> | ||
</ode> | ||
</physics> | ||
</joint> | ||
|
||
<!-- Gimbal vertical arm --> | ||
<link name="cgo3_vertical_arm_link"> | ||
<inertial> | ||
<pose>0.05 0 0.13 0 0 0</pose> | ||
<mass>0.1</mass> | ||
<inertia> | ||
<ixx>0.001</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>0.001</iyy> | ||
<iyz>0</iyz> | ||
<izz>0.001</izz> | ||
</inertia> | ||
</inertial> | ||
<visual name='cgo3_vertical_arm_visual'> | ||
<pose>0.03 0 0.262 0 0 0</pose> | ||
<geometry> | ||
<mesh> | ||
<scale>0.001 0.001 0.001</scale> | ||
<uri>model://x500_gimbal/meshes/cgo3_vertical_arm_remeshed_v1.stl</uri> | ||
</mesh> | ||
</geometry> | ||
<material> | ||
<ambient>.175 .175 .175 1.0</ambient> | ||
<diffuse>.175 .175 .175 1.0</diffuse> | ||
<specular>.175 .175 .175 1.0</specular> | ||
</material> | ||
</visual> | ||
</link> | ||
<joint name='cgo3_vertical_arm_joint' type='revolute'> | ||
<child>cgo3_vertical_arm_link</child> | ||
<parent>cgo3_mount_link</parent> | ||
<pose>0.005 0 0 0 0 0</pose> | ||
<axis> | ||
<xyz>0 0 -1</xyz> | ||
<limit> | ||
<lower>-1e+16</lower> | ||
<upper>1e+16</upper> | ||
<effort>100</effort> | ||
<velocity>-1</velocity> | ||
</limit> | ||
<dynamics> | ||
<damping>0.1</damping> | ||
</dynamics> | ||
</axis> | ||
<physics> | ||
<ode> | ||
<implicit_spring_damper>1</implicit_spring_damper> | ||
<limit> | ||
<!-- testing soft limits --> | ||
<cfm>0.1</cfm> | ||
<erp>0.2</erp> | ||
</limit> | ||
</ode> | ||
</physics> | ||
</joint> | ||
|
||
<!-- Gimbal horizontal arm --> | ||
<link name="cgo3_horizontal_arm_link"> | ||
<inertial> | ||
<pose>0 0 0.1 0 0 0</pose> | ||
<mass>0.1</mass> | ||
<inertia> | ||
<ixx>0.001</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>0.001</iyy> | ||
<iyz>0</iyz> | ||
<izz>0.001</izz> | ||
</inertia> | ||
</inertial> | ||
<visual name='cgo3_horizontal_arm_visual'> | ||
<pose>0.03 0 0.262 0 0 0</pose> | ||
<geometry> | ||
<mesh> | ||
<scale>0.001 0.001 0.001</scale> | ||
<uri>model://x500_gimbal/meshes/cgo3_horizontal_arm_remeshed_v1.stl</uri> | ||
</mesh> | ||
</geometry> | ||
<material> | ||
<ambient>.175 .175 .175 1.0</ambient> | ||
<diffuse>.175 .175 .175 1.0</diffuse> | ||
<specular>.175 .175 .175 1.0</specular> | ||
</material> | ||
</visual> | ||
</link> | ||
<joint name='cgo3_horizontal_arm_joint' type='revolute'> | ||
<child>cgo3_horizontal_arm_link</child> | ||
<parent>cgo3_vertical_arm_link</parent> | ||
<pose>0 0 0.1 0 0 0</pose> | ||
<axis> | ||
<xyz>-1 0 0</xyz> | ||
<limit> | ||
<lower>-0.785398</lower> | ||
<upper>0.785398</upper> | ||
<effort>100</effort> | ||
<velocity>-1</velocity> | ||
</limit> | ||
<dynamics> | ||
<damping>0.1</damping> | ||
</dynamics> | ||
</axis> | ||
<physics> | ||
<ode> | ||
<implicit_spring_damper>1</implicit_spring_damper> | ||
<limit> | ||
<cfm>0.1</cfm> | ||
<erp>0.2</erp> | ||
</limit> | ||
</ode> | ||
</physics> | ||
</joint> | ||
|
||
<!-- Camera --> | ||
<link name="camera_link"> | ||
<pose>0 0 0 0 0 3.141592</pose> | ||
<inertial> | ||
<!-- place holder --> | ||
<pose>0.015 0 0.1 0 0 0</pose> | ||
<mass>0.1</mass> | ||
<inertia> | ||
<ixx>0.001</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>0.001</iyy> | ||
<iyz>0</iyz> | ||
<izz>0.001</izz> | ||
</inertia> | ||
</inertial> | ||
<collision name='cgo3_camera_collision'> | ||
<pose>0.015 0 0.1 0 0 0</pose> | ||
<geometry> | ||
<sphere> | ||
<radius>0.035</radius> | ||
</sphere> | ||
</geometry> | ||
<surface> | ||
<friction> | ||
<ode> | ||
<mu>1</mu> | ||
<mu2>1</mu2> | ||
</ode> | ||
</friction> | ||
<contact> | ||
<ode> | ||
<kp>1e+8</kp> | ||
<kd>1</kd> | ||
<max_vel>0.01</max_vel> | ||
<min_depth>0.001</min_depth> | ||
</ode> | ||
</contact> | ||
</surface> | ||
</collision> | ||
<visual name='cgo3_camera_visual'> | ||
<pose>-0.03 0 0.262 0 0 3.141592</pose> | ||
<geometry> | ||
<mesh> | ||
<scale>0.001 0.001 0.001</scale> | ||
<uri>model://x500_gimbal/meshes/cgo3_camera_remeshed_v1.stl</uri> | ||
</mesh> | ||
</geometry> | ||
<material> | ||
<ambient>.175 .175 .175 1.0</ambient> | ||
<diffuse>.175 .175 .175 1.0</diffuse> | ||
<specular>.175 .175 .175 1.0</specular> | ||
</material> | ||
</visual> | ||
|
||
<sensor name="camera_imu" type="imu"> | ||
<always_on>1</always_on> | ||
<update_rate>250</update_rate> | ||
<imu> | ||
<angular_velocity> | ||
<x> | ||
<noise type="gaussian"> | ||
<mean>0</mean> | ||
<stddev>0.00018665</stddev> | ||
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev> | ||
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time> | ||
</noise> | ||
</x> | ||
<y> | ||
<noise type="gaussian"> | ||
<mean>0</mean> | ||
<stddev>0.00018665</stddev> | ||
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev> | ||
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time> | ||
</noise> | ||
</y> | ||
<z> | ||
<noise type="gaussian"> | ||
<mean>0</mean> | ||
<stddev>0.00018665</stddev> | ||
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev> | ||
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time> | ||
</noise> | ||
</z> | ||
</angular_velocity> | ||
<linear_acceleration> | ||
<x> | ||
<noise type="gaussian"> | ||
<mean>0</mean> | ||
<stddev>0.00186</stddev> | ||
<dynamic_bias_stddev>0.006</dynamic_bias_stddev> | ||
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time> | ||
</noise> | ||
</x> | ||
<y> | ||
<noise type="gaussian"> | ||
<mean>0</mean> | ||
<stddev>0.00186</stddev> | ||
<dynamic_bias_stddev>0.006</dynamic_bias_stddev> | ||
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time> | ||
</noise> | ||
</y> | ||
<z> | ||
<noise type="gaussian"> | ||
<mean>0</mean> | ||
<stddev>0.00186</stddev> | ||
<dynamic_bias_stddev>0.006</dynamic_bias_stddev> | ||
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time> | ||
</noise> | ||
</z> | ||
</linear_acceleration> | ||
</imu> | ||
</sensor> | ||
|
||
<sensor name="camera" type="camera"> | ||
<pose>0 0 0.1 0 0 0</pose> | ||
<camera> | ||
<horizontal_fov>2.0</horizontal_fov> | ||
<image> | ||
<format>R8G8B8</format> | ||
<format>R8G8B8</format> | ||
<width>1280</width> | ||
<height>720</height> | ||
</image> | ||
<clip> | ||
<near>0.05</near> | ||
<far>15000</far> | ||
</clip> | ||
</camera> | ||
<always_on>1</always_on> | ||
<update_rate>10</update_rate> | ||
<visualize>true</visualize> | ||
<topic>camera</topic> | ||
</sensor> | ||
</link> | ||
<joint name='cgo3_camera_joint' type='revolute'> | ||
<child>camera_link</child> | ||
<parent>cgo3_horizontal_arm_link</parent> | ||
<pose>0.01 0 0.1 0 0 0</pose> | ||
<axis> | ||
<xyz>0 -1 0</xyz> | ||
<limit> | ||
<lower>-1.5708</lower> | ||
<upper>0.7854</upper> | ||
<effort>100</effort> | ||
<velocity>-1</velocity> | ||
</limit> | ||
<dynamics> | ||
<damping>0.1</damping> | ||
</dynamics> | ||
</axis> | ||
<physics> | ||
<ode> | ||
<implicit_spring_damper>1</implicit_spring_damper> | ||
<limit> | ||
<!-- testing soft limits --> | ||
<cfm>0.1</cfm> | ||
<erp>0.2</erp> | ||
</limit> | ||
</ode> | ||
</physics> | ||
</joint> | ||
|
||
<!-- Plugins --> | ||
|
||
<plugin | ||
filename="gz-sim-joint-position-controller-system" | ||
name="gz::sim::systems::JointPositionController"> | ||
<joint_name>cgo3_horizontal_arm_joint</joint_name> | ||
<sub_topic>command/gimbal_roll</sub_topic> | ||
<p_gain>0.8</p_gain> | ||
<i_gain>0.035</i_gain> | ||
<d_gain>0.02</d_gain> | ||
<i_max>0</i_max> | ||
<i_min>0</i_min> | ||
<cmd_max>0.3</cmd_max> | ||
<cmd_min>-0.3</cmd_min> | ||
</plugin> | ||
|
||
<plugin | ||
filename="gz-sim-joint-position-controller-system" | ||
name="gz::sim::systems::JointPositionController"> | ||
<joint_name>cgo3_camera_joint</joint_name> | ||
<sub_topic>command/gimbal_pitch</sub_topic> | ||
<p_gain>0.8</p_gain> | ||
<i_gain>0.01245</i_gain> | ||
<d_gain>0.015</d_gain> | ||
<i_max>0</i_max> | ||
<i_min>0</i_min> | ||
<cmd_max>0.3</cmd_max> | ||
<cmd_min>-0.3</cmd_min> | ||
</plugin> | ||
|
||
<plugin | ||
filename="gz-sim-joint-position-controller-system" | ||
name="gz::sim::systems::JointPositionController"> | ||
<joint_name>cgo3_vertical_arm_joint</joint_name> | ||
<sub_topic>command/gimbal_yaw</sub_topic> | ||
<p_gain>0.3</p_gain> | ||
<i_gain>0.01245</i_gain> | ||
<d_gain>0.015</d_gain> | ||
<i_max>0</i_max> | ||
<i_min>0</i_min> | ||
<cmd_max>0.3</cmd_max> | ||
<cmd_min>-0.3</cmd_min> | ||
</plugin> | ||
|
||
</model> | ||
</sdf> |