ppovb5fc7/gazebo/test/worlds/keys_to_joints.world

363 lines
10 KiB
Plaintext
Raw Normal View History

2019-03-25 11:01:43 +08:00
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<gravity>0 0 0</gravity>
<gui fullscreen='0'>
<plugin name='keyboard' filename='libKeyboardGUIPlugin.so'/>
<camera name='user_camera'>
<pose frame=''>4.5 0 11 0.000361 1.57 1.57036</pose>
</camera>
</gui>
<include>
<uri>model://sun</uri>
</include>
<model name='position_teleop'>
<pose>0 0 0.03 -1.57 -0 0</pose>
<link name='link_1'>
<pose>0 0.02141 0 0 -0 0</pose>
<inertial>
<mass>10</mass>
</inertial>
<visual name='visual'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<lighting>1</lighting>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/White</name>
</script>
</material>
</visual>
<collision name='collision'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
</link>
<link name='link_2'>
<pose>-0 -0.03 -0.25 0 -0 0</pose>
<inertial>
<mass>1</mass>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Red</name>
</script>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
</collision>
</link>
<joint name='joint' type='revolute'>
<parent>link_1</parent>
<child>link_2</child>
<pose>0 0 0.25 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<plugin name='keystojoints' filename='libKeysToJointsPlugin.so'>
<!-- u -->
<map key='117' joint='joint' scale='-0.1' type='position' kp='100' ki='0' kd='10'/>
<!-- j -->
<map key='106' joint='joint' scale='0.1' type='position' kp='100' ki='0' kd='10'/>
</plugin>
</model>
<model name='velocity_teleop'>
<pose>3 0 0.03 -1.57 -0 0</pose>
<link name='link_1'>
<pose>0 0.02141 0 0 -0 0</pose>
<inertial>
<mass>10</mass>
</inertial>
<visual name='visual'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<lighting>1</lighting>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/White</name>
</script>
</material>
</visual>
<collision name='collision'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
</link>
<link name='link_2'>
<pose>-0 -0.03 -0.25 0 -0 0</pose>
<inertial>
<mass>1</mass>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Green</name>
</script>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
</collision>
</link>
<joint name='joint' type='revolute'>
<parent>link_1</parent>
<child>link_2</child>
<pose>0 0 0.25 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<plugin name='keystojoints' filename='libKeysToJointsPlugin.so'>
<!-- 8 -->
<map key='56' joint='joint' scale='-0.3' type='velocity' kp='200' ki='0' kd='0'/>
<!-- i -->
<map key='105' joint='joint' scale='0' type='velocity' kp='200' ki='0' kd='0'/>
<!-- k -->
<map key='107' joint='joint' scale='0.3' type='velocity' kp='200' ki='0' kd='0'/>
</plugin>
</model>
<model name='force_teleop'>
<pose>6 0 0.03 -1.57 -0 0</pose>
<link name='link_1'>
<pose>0 0.02141 0 0 -0 0</pose>
<inertial>
<mass>10</mass>
</inertial>
<visual name='visual'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<lighting>1</lighting>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/White</name>
</script>
</material>
</visual>
<collision name='collision'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
</link>
<link name='link_2'>
<pose>-0 -0.03 -0.25 0 -0 0</pose>
<inertial>
<mass>1</mass>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Blue</name>
</script>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
</collision>
</link>
<joint name='joint' type='revolute'>
<parent>link_1</parent>
<child>link_2</child>
<pose>0 0 0.25 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<plugin name='keystojoints' filename='libKeysToJointsPlugin.so'>
<!-- o -->
<map key='111' joint='joint' scale='-1000' type='force'/>
<!-- l -->
<map key='108' joint='joint' scale='1000' type='force'/>
</plugin>
</model>
<model name='multiple_teleop'>
<pose>9 0 0.03 -1.57 -0 0</pose>
<link name='link_1'>
<pose>0 0.02141 0 0 -0 0</pose>
<inertial>
<mass>10</mass>
</inertial>
<visual name='visual'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<lighting>1</lighting>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/White</name>
</script>
</material>
</visual>
<collision name='collision'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
</link>
<link name='link_2'>
<pose>-0 -0.03 -0.25 0 -0 0</pose>
<inertial>
<mass>1</mass>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Yellow</name>
</script>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
</collision>
</link>
<link name='link_3'>
<pose>-0 -0.07 -0.25 0 -0 0</pose>
<inertial>
<mass>1</mass>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Orange</name>
</script>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.057867 0.042821 0.5</size>
</box>
</geometry>
</collision>
</link>
<joint name='joint_2' type='revolute'>
<parent>link_1</parent>
<child>link_2</child>
<pose>0 0 0.25 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name='joint_3' type='revolute'>
<parent>link_1</parent>
<child>link_3</child>
<pose>0 0 0.25 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<plugin name='keystojoints' filename='libKeysToJointsPlugin.so'>
<!-- p -->
<map key='112' joint='joint_2' scale='-0.1' type='position' kp='100' ki='0' kd='10'/>
<!-- ; -->
<map key='59' joint='joint_2' scale='0.1' type='position' kp='100' ki='0' kd='10'/>
<!-- p -->
<map key='112' joint='joint_3' scale='0.1' type='position' kp='100' ki='0' kd='10'/>
<!-- ; -->
<map key='59' joint='joint_3' scale='-0.1' type='position' kp='100' ki='0' kd='10'/>
</plugin>
</model>
</world>
</sdf>