Skip to content
GitLab
Menu
Projects
Groups
Snippets
Loading...
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
U2IS
husky-ensta
Commits
eb869bad
Unverified
Commit
eb869bad
authored
Apr 14, 2020
by
Simon Thomas
Browse files
Initial commit
parent
a933d756
Changes
5
Expand all
Hide whitespace changes
Inline
Side-by-side
husky_description/meshes/accessories/ZED.dae
0 → 100644
View file @
eb869bad
This diff is collapsed.
Click to expand it.
husky_description/meshes/accessories/zed_model.dae
0 → 100644
View file @
eb869bad
This diff is collapsed.
Click to expand it.
husky_description/urdf/accessories/kinect_camera.urdf.xacro
View file @
eb869bad
...
...
@@ -29,49 +29,75 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
name=
"kinect_camera"
>
<xacro:macro
name=
"kinect_camera"
params=
"prefix:=camera robot_namespace:=/"
>
<xacro:arg
name=
"cams_enabled"
default=
"false"
/>
<xacro:arg
name=
"depth_enabled"
default=
"true"
/>
<xacro:macro
name=
"kinect_camera"
params=
"prefix:=zed robot_namespace:=/"
>
<!-- Create kinect reference frame -->
<!-- Add mesh for
kinect
-->
<!-- Add mesh for
zed
-->
<link
name=
"${prefix}_link"
>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0
"
/>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"
0 0 ${M_PI/2}
"
/>
<origin
xyz=
"0 0 0"
rpy=
"
-1.5708 3.14 -1.5708
"
/>
<geometry>
<mesh
filename=
"package://husky_description/meshes/accessories/
kinect
.dae"
/>
<mesh
filename=
"package://husky_description/meshes/accessories/
ZED
.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<box
size=
"0.
07
0.3 0.0
9
"
/>
<box
size=
"0.
175
0.
03
3 0.0
3
"
/>
</geometry>
</collision>
</link>
<joint
name=
"${prefix}_optical_joint"
type=
"fixed"
>
<origin
xyz=
"0 0 0"
rpy=
"-1.5708 0 -1.5708"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<parent
link=
"${prefix}_link"
/>
<child
link=
"${prefix}_depth_optical"
/>
</joint>
<joint
name=
"${prefix}_cam1_joint"
type=
"fixed"
>
<origin
xyz=
"0 -0.06 0"
rpy=
"0 0 0"
/>
<parent
link=
"${prefix}_link"
/>
<child
link=
"${prefix}_cam1_optical"
/>
</joint>
<joint
name=
"${prefix}_cam2_joint"
type=
"fixed"
>
<origin
xyz=
"0 0.06 0"
rpy=
"0 0 0"
/>
<parent
link=
"${prefix}_link"
/>
<child
link=
"${prefix}_cam2_optical"
/>
</joint>
<joint
name=
"${prefix}_frame_joint"
type=
"fixed"
>
<origin
xyz=
"0 0.06 0"
rpy=
"-1.5708 0 -1.5708"
/>
<parent
link=
"${prefix}_link"
/>
<child
link=
"${prefix}_frame_optical"
/>
</joint>
<link
name=
"${prefix}_depth_optical"
/>
<link
name=
"${prefix}_cam1_optical"
/>
<link
name=
"${prefix}_cam2_optical"
/>
<link
name=
"${prefix}_frame_optical"
/>
<gazebo
reference=
"${prefix}_link"
>
<sensor
type=
"depth"
name=
"${prefix}"
>
<xacro:if
value=
"$(arg depth_enabled)"
>
<gazebo
reference=
"${prefix}_depth_optical"
>
<sensor
type=
"depth"
name=
"${prefix}_depth"
>
<always_on>
true
</always_on>
<update_rate>
20
.0
</update_rate>
<update_rate>
1
.0
</update_rate>
<camera>
<horizontal_fov>
${
6
0.0*M_PI/180.0}
</horizontal_fov>
<horizontal_fov>
${
9
0.0*M_PI/180.0}
</horizontal_fov>
<image>
<format>
R8G8B8
</format>
<width>
64
0
</width>
<height>
48
0
</height>
<width>
128
0
</width>
<height>
72
0
</height>
</image>
<clip>
<near>
0.0
5
</near>
<far>
8.
0
</far>
<near>
0.
3
0
</near>
<far>
2
0
</far>
</clip>
</camera>
<plugin
name=
"
kinect
_${prefix}_controller"
filename=
"libgazebo_ros_
openni_kinect
.so"
>
<plugin
name=
"
zed
_${prefix}_controller"
filename=
"libgazebo_ros_
depth_camera
.so"
>
<cameraName>
${prefix}
</cameraName>
<alwaysOn>
true
</alwaysOn>
<updateRate>
10
</updateRate>
...
...
@@ -81,16 +107,64 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<cameraInfoTopicName>
rgb/camera_info
</cameraInfoTopicName>
<depthImageCameraInfoTopicName>
depth/camera_info
</depthImageCameraInfoTopicName>
<frameName>
${prefix}_frame_optical
</frameName>
<baseline>
0.1
</baseline>
<distortion_k1>
0.0
</distortion_k1>
<distortion_k2>
0.0
</distortion_k2>
<distortion_k3>
0.0
</distortion_k3>
<distortion_t1>
0.0
</distortion_t1>
<distortion_t2>
0.0
</distortion_t2>
<pointCloudCutoff>
0.4
</pointCloudCutoff>
<pointCloudCutoff>
0.5
</pointCloudCutoff>
<pointCloudCutoffMax>
25
</pointCloudCutoffMax>
<robotNamespace>
${robot_namespace}
</robotNamespace>
</plugin>
</sensor>
</gazebo>
</xacro:if>
<xacro:if
value=
"$(arg cams_enabled)"
>
<gazebo
reference=
"${prefix}_cam1_optical"
>
<sensor
type=
"camera"
name=
"cam1"
>
<always_on>
true
</always_on>
<update_rate>
20.0
</update_rate>
<camera>
<horizontal_fov>
${90.0*M_PI/180.0}
</horizontal_fov>
<image>
<format>
R8G8B8
</format>
<width>
1280
</width>
<height>
720
</height>
</image>
<clip>
<near>
0.30
</near>
<far>
20
</far>
</clip>
</camera>
<plugin
name=
"camera_controller"
filename=
"libgazebo_ros_camera.so"
>
<cameraName>
${prefix}_cam1
</cameraName>
</plugin>
</sensor>
</gazebo>
<gazebo
reference=
"${prefix}_cam2_optical"
>
<sensor
type=
"camera"
name=
"cam2"
>
<always_on>
true
</always_on>
<update_rate>
20.0
</update_rate>
<camera>
<horizontal_fov>
${90.0*M_PI/180.0}
</horizontal_fov>
<image>
<format>
R8G8B8
</format>
<width>
1280
</width>
<height>
720
</height>
</image>
<clip>
<near>
0.30
</near>
<far>
20
</far>
</clip>
</camera>
<plugin
name=
"camera_controller"
filename=
"libgazebo_ros_camera.so"
>
<cameraName>
${prefix}_cam2
</cameraName>
</plugin>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
husky_description/urdf/husky.urdf.xacro
View file @
eb869bad
...
...
@@ -31,7 +31,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<xacro:arg
name=
"kinect_enabled"
default=
"false"
/>
<xacro:arg
name=
"kinect_xyz"
default=
"$(optenv HUSKY_KINECT_XYZ 0 0 0)"
/>
<xacro:arg
name=
"kinect_rpy"
default=
"$(optenv HUSKY_KINECT_RPY 0 0
.18 3.14
)"
/>
<xacro:arg
name=
"kinect_rpy"
default=
"$(optenv HUSKY_KINECT_RPY 0 0
0
)"
/>
<xacro:property
name=
"husky_front_bumper_extend"
value=
"$(optenv HUSKY_FRONT_BUMPER_EXTEND 0)"
/>
<xacro:property
name=
"husky_rear_bumper_extend"
value=
"$(optenv HUSKY_REAR_BUMPER_EXTEND 0)"
/>
...
...
@@ -44,8 +44,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<xacro:include
filename=
"$(find husky_description)/urdf/wheel.urdf.xacro"
/>
<xacro:include
filename=
"$(find husky_description)/urdf/accessories/kinect_camera.urdf.xacro"
/>
<xacro:include
filename=
"$(find husky_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro"
/>
<xacro:include
filename=
"$(find husky_description)/urdf/accessories/sensor_arch.urdf.xacro"
/>
<!--xacro:include filename="$(find husky_description)/urdf/accessories/sensor_arch.urdf.xacro"/-->
<xacro:property
name=
"M_PI"
value=
"3.14159"
/>
...
...
@@ -138,26 +137,21 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<xacro:if
value=
"$(arg laser_enabled)"
>
<sick_lms1xx_mount
prefix=
"base"
/>
<sick_lms1xx
frame=
"base_laser"
topic=
"scan"
robot_namespace=
"$(arg robot_namespace)"
/>
<joint
name=
"laser_mount_joint"
type=
"fixed"
>
<origin
xyz=
"$(arg laser_xyz)"
rpy=
"$(arg laser_rpy)"
/>
<parent
link=
"top_plate_link"
/>
<child
link=
"base_laser_mount"
/>
</joint>
<xacro:include
filename=
"$(find robosense_description)/urdf/RS-16.urdf.xacro"
/>
<RS-16
parent=
"base_link"
name=
"robosense"
topic=
"/rs_points"
hz=
"20"
samples=
"900"
gpu=
"true"
>
<origin
xyz=
"0 0 0.4"
rpy=
"0 0 0"
/>
</RS-16>
</xacro:if>
<xacro:if
value=
"$(arg kinect_enabled)"
>
<xacro:sensor_arch
prefix=
""
parent=
"top_plate_link"
>
<
!--
xacro:sensor_arch prefix="" parent="top_plate_
front_
link">
<origin xyz="-0.35 0 0.51" rpy="0 0 -3.14"/>
</xacro:sensor_arch>
</xacro:sensor_arch
--
>
<joint
name=
"kinect_frame_joint"
type=
"fixed"
>
<origin
xyz=
"$(arg kinect_xyz)"
rpy=
"$(arg kinect_rpy)"
/>
<parent
link=
"
sensor_arch_mou
nt_link"
/>
<parent
link=
"
top_plate_fro
nt_link"
/>
<child
link=
"camera_link"
/>
</joint>
...
...
@@ -171,7 +165,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
</gazebo>
<gazebo>
<plugin
name=
"imu_controller"
filename=
"lib
hector_
gazebo_ros_imu.so"
>
<plugin
name=
"imu_controller"
filename=
"libgazebo_ros_imu.so"
>
<robotNamespace>
$(arg robot_namespace)
</robotNamespace>
<updateRate>
50.0
</updateRate>
<bodyName>
base_link
</bodyName>
...
...
@@ -202,6 +196,6 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
</gazebo>
<!-- Optional custom includes. -->
<xacro:include
filename=
"$(arg urdf_extras)"
/>
<
!--
xacro:include filename="$(arg urdf_extras)" /
--
>
</robot>
husky_gazebo/launch/husky_empty_world.launch
View file @
eb869bad
...
...
@@ -28,7 +28,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<arg
name=
"world_name"
default=
"worlds/empty.world"
/>
<arg
name=
"laser_enabled"
default=
"true"
/>
<arg
name=
"kinect_enabled"
default=
"
fals
e"
/>
<arg
name=
"kinect_enabled"
default=
"
tru
e"
/>
<include
file=
"$(find gazebo_ros)/launch/empty_world.launch"
>
<arg
name=
"world_name"
value=
"$(arg world_name)"
/>
<!-- world_name is wrt GAZEBO_RESOURCE_PATH environment variable -->
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment