Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make realsense Parametric #42

Open
wants to merge 2 commits into
base: dev/noetic
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion stretch_gazebo/config/sim.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -318,7 +318,7 @@ Visualization Manager:
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /realsense/depth/color/points
Topic: /camera/depth/color/points
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Expand Down
4 changes: 2 additions & 2 deletions stretch_gazebo/launch/gazebo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<arg name="model" default="$(find stretch_gazebo)/urdf/stretch_gazebo.urdf.xacro"/>
<arg name="gpu_lidar" default="false"/>
<arg name="visualize_lidar" default="false"/>
<arg name="world" default="worlds/empty.world"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Did you mean to remove this argument?

<arg name="realsense" default="false"/>

<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world)" />
Expand All @@ -21,7 +21,7 @@
<arg name="verbose" value="true"/>
</include>

<param name="robot_description" command="$(find xacro)/xacro $(arg model) gpu_lidar:=$(arg gpu_lidar) visualize_lidar:=$(arg visualize_lidar)" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model) gpu_lidar:=$(arg gpu_lidar) visualize_lidar:=$(arg visualize_lidar) realsense:=$(arg realsense)" />

<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
Expand Down
251 changes: 127 additions & 124 deletions stretch_gazebo/urdf/stretch_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_description">
<xacro:arg name="gpu_lidar" default="false" />
<xacro:arg name="visualize_lidar" default="false" />
<xacro:arg name="realsense" default="false" />

<xacro:include filename="$(find stretch_description)/urdf/stretch_main.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_aruco.xacro" />
Expand Down Expand Up @@ -70,130 +71,132 @@
<!-- Sensors -->

<!-- Realsense D435i -->
<gazebo reference="camera_color_frame">
<sensor name="color" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_infra1_frame">
<sensor name="ired1" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_infra2_frame">
<sensor name="ired2" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_depth_frame">
<sensor name="depth" type="depth">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin name="camera" filename="librealsense_gazebo_plugin.so">
<depthUpdateRate>30</depthUpdateRate>
<colorUpdateRate>30</colorUpdateRate>
<infraredUpdateRate>30</infraredUpdateRate>
<depthTopicName>depth/image_raw</depthTopicName>
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
<colorTopicName>color/image_raw</colorTopicName>
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
<infrared1TopicName>infrared/image_raw</infrared1TopicName>
<infrared1CameraInfoTopicName>infrared/camera_info</infrared1CameraInfoTopicName>
<infrared2TopicName>infrared2/image_raw</infrared2TopicName>
<infrared2CameraInfoTopicName>infrared2/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.1</rangeMinDepth>
<rangeMaxDepth>10</rangeMaxDepth>
<pointCloud>1</pointCloud>
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
<pointCloudCutoff>0.15</pointCloudCutoff>
<pointCloudCutoffMax>10</pointCloudCutoffMax>
</plugin>
</gazebo>
<xacro:if value="$(arg realsense)">
<gazebo reference="camera_color_frame">
<sensor name="color" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_infra1_frame">
<sensor name="ired1" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_infra2_frame">
<sensor name="ired2" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_depth_frame">
<sensor name="depth" type="depth">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin name="camera" filename="librealsense_gazebo_plugin.so">
<depthUpdateRate>30</depthUpdateRate>
<colorUpdateRate>30</colorUpdateRate>
<infraredUpdateRate>30</infraredUpdateRate>
<depthTopicName>depth/image_raw</depthTopicName>
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
<colorTopicName>color/image_raw</colorTopicName>
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
<infrared1TopicName>infrared/image_raw</infrared1TopicName>
<infrared1CameraInfoTopicName>infrared/camera_info</infrared1CameraInfoTopicName>
<infrared2TopicName>infrared2/image_raw</infrared2TopicName>
<infrared2CameraInfoTopicName>infrared2/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.1</rangeMinDepth>
<rangeMaxDepth>10</rangeMaxDepth>
<pointCloud>1</pointCloud>
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
<pointCloudCutoff>0.15</pointCloudCutoff>
<pointCloudCutoffMax>10</pointCloudCutoffMax>
</plugin>
</gazebo>
</xacro:if>

<gazebo reference="camera_gyro_frame">
<gravity>true</gravity>
Expand Down