turtlebot3_simulations/turtlebot3_manipulation_gazebo/gazebo/turtlebot3_waffle_pi.gazebo.xacro

166 lines
4.8 KiB
XML

<?xml version="1.0"?>
<!--
Copied and modified from turtlebot3 example:
https://github.com/ROBOTIS-GIT/turtlebot3/blob/kinetic-devel/turtlebot3_description/urdf/turtlebot3_waffle_pi_for_open_manipulator.gazebo.xacro
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="turtlebot3_waffle_pi_gazebo" params="prefix">
<xacro:property name="laser_visual" value="true"/>
<xacro:property name="camera_visual" value="true"/>
<xacro:property name="imu_visual" value="true"/>
<gazebo reference="${prefix}base_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="${prefix}wheel_left_link">
<mu1>10000</mu1>
<mu2>10000</mu2>
<kp>500000.0</kp>
<kd>10.0</kd>
<minDepth>0.001</minDepth>
<maxVel>0.1</maxVel>
<fdir1>1 0 0</fdir1>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="${prefix}wheel_right_link">
<mu1>10000</mu1>
<mu2>10000</mu2>
<kp>500000.0</kp>
<kd>10.0</kd>
<minDepth>0.001</minDepth>
<maxVel>0.1</maxVel>
<fdir1>1 0 0</fdir1>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="${prefix}caster_back_right_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>1000000.0</kp>
<kd>100.0</kd>
<minDepth>0.001</minDepth>
<maxVel>1.0</maxVel>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="${prefix}caster_back_left_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>1000000.0</kp>
<kd>100.0</kd>
<minDepth>0.001</minDepth>
<maxVel>1.0</maxVel>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="${prefix}imu_link">
<material>Gazebo/Grey</material>
<sensor type="imu" name="imu">
<always_on>true</always_on>
<update_rate>100.0</update_rate>
<visualize>${imu_visual}</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
<ros>
<namespace></namespace>
<remapping>cmd_vel:=cmd_vel</remapping>
<remapping>odom:=odom</remapping>
</ros>
<left_joint>wheel_left_joint</left_joint>
<right_joint>wheel_right_joint</right_joint>
<wheel_separation>0.287</wheel_separation>
<wheel_diameter>0.066</wheel_diameter>
<max_wheel_torque>20</max_wheel_torque>
<max_wheel_acceleration>1.0</max_wheel_acceleration>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>false</publish_wheel_tf>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin>
</gazebo>
<gazebo reference="${prefix}base_scan">
<material>Gazebo/FlatBlack</material>
<sensor type="ray" name="lds_lfcd_sensor">
<pose>0 0 0 0 0 0</pose>
<always_on>true</always_on>
<update_rate>5.0</update_rate>
<visualize>${laser_visual}</visualize>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>0.0</min_angle>
<max_angle>6.28319</max_angle>
</horizontal>
</scan>
<range>
<min>0.120</min>
<max>3.5</max>
<resolution>0.015</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace></namespace>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
</sensor>
</gazebo>
<gazebo reference="${prefix}camera_rgb_frame">
<sensor type="camera" name="pi_camera">
<update_rate>30</update_rate>
<always_on>true</always_on>
<visualize>${camera_visual}</visualize>
<camera>
<horizontal_fov>1.085595</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.03</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace></namespace>
<remapping>image_raw:=image_raw</remapping>
<remapping>camera_info:=camera_info</remapping>
</ros>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>