Commit 16b11232 authored by Darby Lim's avatar Darby Lim
Browse files

add waffle_pi urdf and gazebo

parent d743de3a
No related merge requests found
Showing with 31 additions and 34 deletions
+31 -34
<?xml version="1.0"?>
<robot name="turtlebot3_waffle_sim" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="turtlebot3_waffle_pi_sim" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="laser_visual" default="false"/>
<xacro:arg name="camera_visual" default="false"/>
<xacro:arg name="imu_visual" default="false"/>
<xacro:arg name="r200_cam_rgb_px" default="0.005"/>
<xacro:arg name="r200_cam_rgb_py" default="0.018"/>
<xacro:arg name="r200_cam_rgb_pz" default="0.013"/>
<xacro:arg name="r200_cam_depth_offset" default="0.01"/>
<gazebo>
<plugin name="turtlebot3_waffle_controller" filename="libgazebo_ros_diff_drive.so">
<plugin name="turtlebot3_waffle_pi_controller" filename="libgazebo_ros_diff_drive.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
......@@ -144,46 +139,38 @@
</sensor>
</gazebo>
<!--link : https://www.raspberrypi.org/documentation/hardware/camera/-->
<gazebo reference="camera_link">
<sensor type="depth" name="realsense_R200">
<pose>$(arg r200_cam_rgb_px) $(arg r200_cam_rgb_py) $(arg r200_cam_rgb_pz) 0 0 0</pose>
<sensor type="camera" name="Pi Camera">
<pose>0.003 0.011 0.008 0 0 0</pose>
<always_on>true</always_on>
<visualize>$(arg camera_visual)</visualize>
<camera>
<horizontal_fov>1.02974</horizontal_fov>
<horizontal_fov>1.085595</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<depth_camera></depth_camera>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<pose>$(arg r200_cam_depth_offset) 0 0 0 0 0</pose>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>camera</cameraName>
<frameName>camera_link</frameName>
<updateRate>30.0</updateRate>
<cameraName>camera</cameraName>
<frameName>camera_link</frameName>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudCutoff>0.4</pointCloudCutoff>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<CxPrime>0.0</CxPrime>
<Cx>0.0</Cx>
<Cy>0.0</Cy>
<focalLength>0.0</focalLength>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<focalLength>0.003</focalLength>
</plugin>
</sensor>
</gazebo>
......
<?xml version="1.0" ?>
<robot name="turtlebot3_waffle" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="turtlebot3_waffle_pi" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find turtlebot3_description)/urdf/common_properties.xacro"/>
<xacro:include filename="$(find turtlebot3_description)/urdf/turtlebot3_waffle_pi.gazebo.xacro"/>
......
<launch>
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle]"/>
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<!-- Turtlebot3 -->
<include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch" />
......
obstacle_range: 2.5
raytrace_range: 3.5
footprint: [[-0.205, -0.145], [-0.205, 0.145], [0.077, 0.145], [0.077, -0.145]]
#robot_radius: 0.17
inflation_radius: 0.20
cost_scaling_factor: 0.5
map_type: costmap
transform_tolerance: 0.2
observation_sources: scan
scan: {data_type: LaserScan, topic: scan, marking: true, clearing: true}
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment