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

Ros1-legacy #3077

Open
wants to merge 2 commits into
base: ros1-legacy
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 realsense2_camera/launch/rs_camera.launch
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
<arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/>
<arg name="pointcloud_texture_index" default="0"/>
<arg name="allow_no_texture_points" default="false"/>
<arg name="ordered_pc" default="false"/>
<arg name="ordered_pc" default="true"/>

<arg name="enable_sync" default="false"/>
<arg name="align_depth" default="false"/>
Expand Down
28 changes: 28 additions & 0 deletions realsense2_description/launch/gazebo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<launch>

<!-- these are the arguments you can pass this launch file, for example paused:=true -->
<arg name="start_gazebo" default="true"/>
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<arg name="model" default="$(find realsense2_description)/urdf/test_d435_camera.urdf.xacro"/>

<!-- robot description to load in rviz or gazebo -->
<param name="robot_description" command="$(find xacro)/xacro $(arg model)" />

<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include if="$(arg start_gazebo)" file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>

<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
args="-z 0.0 -x 0.0 -y 0.0 -unpause -urdf -model robot -param robot_description" respawn="false" output="screen" />
</launch>

21 changes: 21 additions & 0 deletions realsense2_description/launch/view_d435_model_rviz_gazebo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<launch>
<!-- arguments for the urdf xacro file, rviz visualization and namespace -->
<arg name="start_gazebo" default="true"/>
<arg name="model" default="$(find realsense2_description)/urdf/test_d435_camera.urdf.xacro"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model) use_nominal_extrinsics:=true add_plug:=true" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="30.0" />
</node>

<!-- this will include the launch file for gazebo given the model -->
<include file="$(find realsense2_description)/launch/gazebo.launch">
<arg name="model" value="$(arg model)" />
<!-- We wont need to start gazebo if kortex does it for us -->
<arg name="start_gazebo" value="$(arg start_gazebo)" />
</include>

<arg name="gui" default="True" />
<param name="use_gui" value="$(arg gui)" />
<!-- <node name="rviz" pkg="rviz" type="rviz" args="-d $(find realsense2_description)/rviz/urdf.rviz" required="true" /> -->
</launch>

2 changes: 1 addition & 1 deletion realsense2_description/rviz/urdf.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ Visualization Manager:
camera_infra2_frame:
camera_infra2_optical_frame:
{}
Update Interval: 0
Update Interval: 5
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Expand Down
147 changes: 147 additions & 0 deletions realsense2_description/urdf/_d435.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,147 @@
<?xml version="1.0"?>

<!--
License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 PAL Robotics, S.L. All Rights Reserved

This is the Gazebo URDF model for the Intel RealSense D435 camera
-->

<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="gazebo_d435" params="camera_name reference_link topics_ns depth_optical_frame color_optical_frame infrared1_optical_frame infrared2_optical_frame publish_pointcloud:=true" >

<!-- Load parameters to model's main link-->
<xacro:property name="deg_to_rad" value="0.01745329251994329577" />
<gazebo reference="${reference_link}">
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<!--<mu>1</mu>-->
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<!--<slip1>0</slip1>
<slip2>0</slip2>-->
<kp>1e+13</kp>
<kd>1</kd>
<!--<max_vel>0.01</max_vel>
<min_depth>0</min_depth>-->
<sensor name="${camera_name}color" type="camera">
<camera name="${camera_name}">
<horizontal_fov>${69.4*deg_to_rad}</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>1</visualize>
</sensor>
<sensor name="${camera_name}ired1" type="camera">
<camera name="${camera_name}">
<horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
<image>
<width>1280</width>
<height>720</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.05</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="${camera_name}ired2" type="camera">
<camera name="${camera_name}">
<horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
<image>
<width>1280</width>
<height>720</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.05</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="${camera_name}depth" type="depth">
<camera name="${camera_name}">
<horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.100</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>

<gazebo>
<plugin name="${topics_ns}" filename="librealsense_gazebo_plugin.so">
<prefix>${camera_name}</prefix>
<depthUpdateRate>30.0</depthUpdateRate>
<colorUpdateRate>30.0</colorUpdateRate>
<infraredUpdateRate>30.0</infraredUpdateRate>
<depthTopicName>depth/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>${color_optical_frame}</colorOpticalframeName>
<depthOpticalframeName>${depth_optical_frame}</depthOpticalframeName>
<infrared1OpticalframeName>${infrared1_optical_frame}</infrared1OpticalframeName>
<infrared2OpticalframeName>${infrared2_optical_frame}</infrared2OpticalframeName>
<rangeMinDepth>0.2</rangeMinDepth>
<rangeMaxDepth>10.0</rangeMaxDepth>
<pointCloud>${publish_pointcloud}</pointCloud>
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
<pointCloudCutoff>0.25</pointCloudCutoff>
<pointCloudCutoffMax>9.0</pointCloudCutoffMax>
</plugin>
</gazebo>

</xacro:macro>
</robot>
Loading