Skip to content

Commit

Permalink
Add depth camera to jackal sim
Browse files Browse the repository at this point in the history
  • Loading branch information
mmattamala committed Mar 23, 2024
1 parent a91cbf5 commit 38b617d
Show file tree
Hide file tree
Showing 5 changed files with 125 additions and 17 deletions.
30 changes: 14 additions & 16 deletions wild_visual_navigation_jackal/launch/sim.launch
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
<?xml version="1.0" encoding="utf-8"?>
<launch>
<!-- Extras to add required sensors -->
<!-- <arg name="extras_file" default="$(find wild_visual_navigation_sim)/urdf/extras.xacro"/>
<env name="JACKAL_URDF_EXTRAS" value="$(arg extras_file)"/> -->

<!-- Default simulation args -->
<arg name="use_sim_time" default="true" />
<arg name="gui" default="true" />
<arg name="headless" default="false" />
<arg name="world_name" default="$(find wild_visual_navigation_sim)/worlds/outdoor.world" />
<arg name="jackal_config" value="front_flea3" /> <!-- add camera -->
<arg name="world_name" default="$(find wild_visual_navigation_jackal)/worlds/outdoor.world" />

<arg name="x" default="0" />
<arg name="y" default="0" />
<arg name="z" default="1" />
<arg name="yaw" default="0" />

<!-- Launch Gazebo with the specified world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
Expand All @@ -20,15 +20,13 @@
<arg name="world_name" value="$(arg world_name)" />
</include>

<!-- Spawn Jackal -->
<include file="$(find jackal_gazebo)/launch/spawn_jackal.launch">
<arg name="x" value="0" />
<arg name="y" value="0" />
<arg name="z" value="1.0" />
<arg name="yaw" value="0" />
<arg name="config" value="$(arg jackal_config)" />
<arg name="joystick" value="false" />
</include>
<!-- Load Jackal's description, controllers, and spawn-->
<param name="robot_description"
command="$(find wild_visual_navigation_jackal)/urdf/load_xacro.sh" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

<include file="$(find jackal_control)/launch/control.launch"/>


<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
args="-urdf -model jackal -param robot_description -x $(arg x) -y $(arg y) -z $(arg z) -R 0 -P 0 -Y $(arg yaw)" />
</launch>
96 changes: 96 additions & 0 deletions wild_visual_navigation_jackal/urdf/depth_camera.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
<?xml version="1.0"?>
<robot name="depth_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="depth_camera"
params="name parent x:=0.0
y:=0.0
z:=0.0
roll:=0.0
pitch:=0.0
yaw:=0.0">
<!-- param name: Name of the camera -->
<!-- param parent: Parent link for camera joint -->
<xacro:property name="camera_size" value="0.02" />

<!--create
link from parent -->
<joint name="${parent}_to_${name}" type="fixed">
<origin xyz="${x} ${y} ${z}" rpy="${roll} ${pitch} ${yaw}" />
<parent link="${parent}" />
<child link="${name}_link" />
</joint>

<!-- Create camera -->
<link name="${name}_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${camera_size}" radius="${camera_size}" />
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="0 ${pi/2} 0" />
<geometry>
<cylinder length="${camera_size}" radius="${camera_size}" />
</geometry>
<material name="blue">
<color rgba="0 0 .8 1" />
</material>
</visual>

<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>

<gazebo reference="${name}_link">
<turnGravityOff>true</turnGravityOff>
<sensor type="depth" name="${name}">
<update_rate>30</update_rate>
<camera>
<!-- 75x65 degree FOV for the depth sensor -->
<horizontal_fov>1.518</horizontal_fov>
<vertical_fov>1.012</vertical_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<!-- give the color sensor a maximum range of 50m so that the simulation
renders nicely -->
<near>0.01</near>
<far>50.0</far>
</clip>
</camera>
<plugin name="${name}_controller" filename="libgazebo_ros_openni_kinect.so">
<robotNamespace>/</robotNamespace>
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>${name}</cameraName>
<imageTopicName>/${name}/color/image_raw</imageTopicName>
<cameraInfoTopicName>/${name}/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/${name}/depth/image_rect_raw</depthImageTopicName>
<depthImageInfoTopicName>/${name}/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/${name}/depth/color/points</pointCloudTopicName>
<frameName>${name}_link</frameName>
<pointCloudCutoff>0.105</pointCloudCutoff>
<pointCloudCutoffMax>8.0</pointCloudCutoffMax>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
10 changes: 10 additions & 0 deletions wild_visual_navigation_jackal/urdf/extras.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Add camera -->
<xacro:include filename="$(find wild_visual_navigation_jackal)/urdf/depth_camera.xacro" />
<xacro:depth_camera name="depth_camera"
parent="front_mount"
x="0.1"
y="0.0"
z="0.02"
pitch="${pi/180 * 20}"/>
</robot>
4 changes: 4 additions & 0 deletions wild_visual_navigation_jackal/urdf/load_xacro.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
#!/bin/bash
# This is a workaround to set the JACKAL_URDF_EXTRAS path
export JACKAL_URDF_EXTRAS="$(rospack find wild_visual_navigation_jackal)/urdf/extras.xacro"
xacro $(rospack find jackal_description)/urdf/jackal.urdf.xacro
2 changes: 1 addition & 1 deletion wild_visual_navigation_jackal/worlds/outdoor.world
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,7 @@
<model name="tree8">
<static>true</static>
<link name="tree8_link">
<pose>9 -4 -0.5 0 0 0.5</pose>
<pose>9 -4 -1.0 0 0 0.5</pose>
<collision name="tree8_collision">
<geometry>
<mesh>
Expand Down

0 comments on commit 38b617d

Please sign in to comment.