You can start editing with urdf file. Edit the file catkin_ws/src/turtlebot3/turtlebot3_description/urdf/turtlebot3_burger.gazebo.xacro
.
remove the following part.
<gazebo reference="base_scan">
<material>Gazebo/FlatBlack</material>
<sensor type="ray" name="lds_lfcd_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg laser_visual)</visualize>
<update_rate>5</update_rate>
<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_laser.so">
<topicName>scan</topicName>
<frameName>base_scan</frameName>
</plugin>
</sensor>
</gazebo>
and add your sensor.
You will need to adjust the sensor_link
name and also change it in the joints
.
In the file catkin_ws/src/turtlebot3/turtlebot3_description/urdf/turtlebot3_burger.urdf.xacro
replace the following with your appropriate sensor name.
<joint name="scan_joint" type="fixed">
<parent link="base_link"/>
<child link="base_scan"/>
<origin xyz="-0.032 0 0.172" rpy="0 0 0"/>
</joint>
<link name="base_scan">
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot3_description/meshes/sensors/lds.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0.015 0 -0.0065" rpy="0 0 0"/>
<geometry>
<cylinder length="0.0315" radius="0.055"/>
</geometry>
</collision>
<inertial>
<mass value="0.114" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
or use the same names in your new sensor.
For reference this is the d435 sensor plugin I use.
<?xml version="1.0" encoding="UTF-8"?>
<sdf version="1.5">
<model name="d435">
<pose>0 0 0 0 0 0</pose>
<link name="base_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0.0175 0.0125 0 -0 0</pose>
<mass>0.564</mass>
<inertia>
<ixx>0.00388124</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00049894</iyy>
<iyz>0</iyz>
<izz>0.00387926</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>0 0 0.0125 0 -0 0</pose>
<geometry>
<box>
<size>0.025 0.09 0.025</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>1e+13</kp>
<kd>1</kd>
</ode>
</contact>
<friction>
<ode>
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0.0125 1.5708 -0 1.5708</pose>
<geometry>
<mesh>
<uri>model://d435/meshes/d435.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.5 0.5 0.5 1</ambient>
<diffuse>0.9 0.9 0.9 0.5</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 1</emissive>
<shader type="pixel">
<normal_map>__default__</normal_map>
</shader>
<lighting>1</lighting>
</material>
<cast_shadows>1</cast_shadows>
</visual>
<sensor name="cameracolor" type="camera">
<pose>0 0 0 0 0 0</pose>
<camera name="camera">
<horizontal_fov>1.500</horizontal_fov>
<image>
<width>640</width>
<height>360</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>30</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.0</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="cameraired1" type="camera">
<pose>0 0 0 0 0 0</pose>
<camera name="camera">
<horizontal_fov>1.500</horizontal_fov>
<image>
<width>640</width>
<height>360</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>30</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.0</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
<pose>0 0.0175 0.0125 0 -0 0</pose>
</sensor>
<sensor name="cameraired2" type="camera">
<pose>0 0.05 0 0 0 0</pose>
<camera name="camera">
<horizontal_fov>1.500</horizontal_fov>
<image>
<width>640</width>
<height>360</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>30</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.0</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="cameradepth" type="depth">
<pose>0 0 0 0 0 0</pose>
<camera name="camera">
<horizontal_fov>1.48702</horizontal_fov>
<image>
<width>640</width>
<height>360</height>
</image>
<clip>
<near>0.1</near>
<far>20</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.0</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</link>
<plugin name="camera" filename="librealsense_gazebo_plugin.so">
<prefix>camera</prefix>
<depthUpdateRate>30.0</depthUpdateRate>
<colorUpdateRate>30.0</colorUpdateRate>
<infraredUpdateRate>30.0</infraredUpdateRate>
<depthTopicName>depth_aligned_to_color_and_infra1/image_raw</depthTopicName>
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
<colorTopicName>color/image_raw</colorTopicName>
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
<infrared1TopicName>infra1/image_raw</infrared1TopicName>
<infrared1CameraInfoTopicName>infra1/camera_info</infrared1CameraInfoTopicName>
<infrared2TopicName>infra2/image_raw</infrared2TopicName>
<infrared2CameraInfoTopicName>infra2/camera_info</infrared2CameraInfoTopicName>
<colorOpticalframeName>camera_color_optical_frame</colorOpticalframeName>
<depthOpticalframeName>camera_depth_optical_frame</depthOpticalframeName>
<infrared1OpticalframeName>camera_left_ir_optical_frame</infrared1OpticalframeName>
<infrared2OpticalframeName>camera_right_ir_optical_frame</infrared2OpticalframeName>
<rangeMinDepth>0.01</rangeMinDepth>
<rangeMaxDepth>20.0</rangeMaxDepth>
<pointCloud>1</pointCloud>
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
<pointCloudCutoff>0.01</pointCloudCutoff>
<pointCloudCutoffMax>20.0</pointCloudCutoffMax>
</plugin>
</model>
</sdf>
You can adjust the topics you need. Hope this helps.