sentry_plan_control/plc_bringup/urdf/myrobot

484 lines
14 KiB
Plaintext

<sdf version='1.7'>
<model name='robot'>
<link name='base_footprint'>
<inertial>
<pose>0.000456 0 0.000638 0 -0 0</pose>
<mass>8.23</mass>
<inertia>
<ixx>0.100968</ixx>
<ixy>0</ixy>
<ixz>-0.000653858</ixz>
<iyy>0.101435</iyy>
<iyz>0</iyz>
<izz>0.10047</izz>
</inertia>
</inertial>
<collision name='base_footprint_fixed_joint_lump__base_link_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<box>
<size>0.2 0.3 0.1</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name='base_footprint_fixed_joint_lump__camera_link_collision_1'>
<pose>0.125 0 0.175 0 -0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name='base_footprint_fixed_joint_lump__laser_frame_collision_2'>
<pose>0.125 0 0.225 0 -0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name='base_footprint_fixed_joint_lump__imu_link_collision_3'>
<pose>0.125 0 0.125 0 -0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</collision>
<visual name='base_footprint_fixed_joint_lump__base_link_visual'>
<pose>0 0 0.05 0 -0 1.5708</pose>
<geometry>
<box>
<size>0.2 0.3 0.1</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Orange</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name='base_footprint_fixed_joint_lump__camera_link_visual_1'>
<pose>0.125 0 0.175 0 -0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Red</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name='base_footprint_fixed_joint_lump__laser_frame_visual_2'>
<pose>0.125 0 0.225 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>/home/hshine/plan_control_ws/src/plc_bringup/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<visual name='base_footprint_fixed_joint_lump__imu_link_visual_3'>
<pose>0.125 0 0.125 0 -0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</visual>
<gravity>1</gravity>
<sensor name='camera1' type='camera'>
<update_rate>30</update_rate>
<camera name='head'>
<horizontal_fov>1.39626</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name='camera_controller' filename='libgazebo_ros_camera.so'>
<alwaysOn>1</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>/</cameraName>
<imageTopicName>cam</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
<pose>0.125 0 0.175 0 -0 0</pose>
</sensor>
<sensor name='head_hokuyo_sensor' type='ray'>
<always_on>1</always_on>
<visualize>0</visualize>
<update_rate>15</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.14159</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>30</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name='turtlebot3_laserscan' filename='libgazebo_ros_ray_sensor.so'>
<ros>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frameName>laser_frame</frameName>
</plugin>
<pose>0.125 0 0.225 0 -0 0</pose>
</sensor>
</link>
<joint name='base_to_wheel1' type='revolute'>
<pose relative_to='base_footprint'>0.1 0.13 0 -1.5708 0 0</pose>
<parent>base_footprint</parent>
<child>wheel_1</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='wheel_1'>
<pose relative_to='base_to_wheel1'>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.5</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<collision name='wheel_1_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='wheel_1_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Red</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
</link>
<joint name='base_to_wheel2' type='revolute'>
<pose relative_to='base_footprint'>-0.1 0.13 0 -1.5708 0 0</pose>
<parent>base_footprint</parent>
<child>wheel_2</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<effort>100</effort>
<velocity>100</velocity>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='wheel_2'>
<pose relative_to='base_to_wheel2'>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.5</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<collision name='wheel_2_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='wheel_2_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
</link>
<joint name='base_to_wheel3' type='revolute'>
<pose relative_to='base_footprint'>0.1 -0.13 0 -1.5708 0 0</pose>
<parent>base_footprint</parent>
<child>wheel_3</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='wheel_3'>
<pose relative_to='base_to_wheel3'>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.5</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<collision name='wheel_3_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='wheel_3_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Red</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
</link>
<joint name='base_to_wheel4' type='revolute'>
<pose relative_to='base_footprint'>-0.1 -0.13 0 -1.5708 0 0</pose>
<parent>base_footprint</parent>
<child>wheel_4</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='wheel_4'>
<pose relative_to='base_to_wheel4'>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.5</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<collision name='wheel_4_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='wheel_4_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.05</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
</link>
<static>0</static>
<!-- <plugin name='skid_steer_drive' filename='libgazebo_ros_diff_drive.so'>
<num_wheel_pairs>2</num_wheel_pairs>
<left_joint>base_to_wheel1</left_joint>
<right_joint>base_to_wheel3</right_joint>
<left_joint>base_to_wheel2</left_joint>
<right_joint>base_to_wheel4</right_joint>
<wheel_separation>0.26</wheel_separation>
<wheel_separation>0.26</wheel_separation>
<wheel_diameter>0.12</wheel_diameter>
<wheel_diameter>0.12</wheel_diameter>
<max_wheel_torque>20</max_wheel_torque>
<max_wheel_acceleration>1.0</max_wheel_acceleration>
<publish_odom>1</publish_odom>
<publish_odom_tf>1</publish_odom_tf>
<publish_wheel_tf>1</publish_wheel_tf>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin> -->
<plugin name="mecanum_controller" filename="libgazebo_ros_planar_move.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<leftFrontJoint>base_to_wheel1</leftFrontJoint>
<rightFrontJoint>base_to_wheel3</rightFrontJoint>
<leftRearJoint>base_to_wheel2</leftRearJoint>
<rightRearJoint>base_to_wheel4</rightRearJoint>
<odometryRate>100</odometryRate>
<robotBaseFrame>base_footprint</robotBaseFrame>
<broadcastTF>1</broadcastTF>
</plugin>
<plugin name='turtlebot3_joint_state' filename='libgazebo_ros_joint_state_publisher.so'>
<ros>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>base_to_wheel1</joint_name>
<joint_name>base_to_wheel2</joint_name>
<joint_name>base_to_wheel3</joint_name>
<joint_name>base_to_wheel4</joint_name>
</plugin>
</model>
</sdf>