Skip to content

Commit 62503a8

Browse files
committed
Add Velodyne in simulation.
Signed-off-by: Jelmer de Wolde <[email protected]>
1 parent 0e24e38 commit 62503a8

File tree

7 files changed

+183
-8
lines changed

7 files changed

+183
-8
lines changed

dockerfiles/install_scripts/realsense.sh renamed to dockerfiles/install_scripts/sensors.sh

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,9 +3,13 @@
33
# SPDX-License-Identifier: Apache-2.0
44

55
set -e
6-
7-
pip install pyrealsense2
86
apt update
7+
8+
# Realsense:
99
apt install -y \
1010
ros-humble-realsense2-camera \
1111
ros-humble-realsense2-description
12+
pip install pyrealsense2
13+
14+
# Velodyne:
15+
apt install -y ros-humble-velodyne-description

dockerfiles/rcdt_robotics.Dockerfile

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@ RUN ./rosboard.sh
3232
COPY ./install_scripts/pyflow.sh .
3333
RUN ./pyflow.sh
3434

35-
COPY ./install_scripts/realsense.sh .
36-
RUN ./realsense.sh
35+
COPY ./install_scripts/sensors.sh .
36+
RUN ./sensors.sh
3737

3838
COPY ./install_scripts/sphinx.sh .
3939
RUN ./sphinx.sh

ros2_ws/src/rcdt_panther/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ install(
1717

1818
# Shared folders:
1919
install(
20-
DIRECTORY launch config
20+
DIRECTORY launch config urdf
2121
DESTINATION share/${PROJECT_NAME}
2222
)
2323

ros2_ws/src/rcdt_panther/launch/panther.launch.py

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,17 @@
1212
)
1313

1414
use_rviz_arg = LaunchArgument("rviz", True, [True, False])
15+
use_velodyne_arg = LaunchArgument("velodyne", False, [True, False])
1516

1617

1718
def launch_setup(context: LaunchContext) -> None:
1819
use_rviz = use_rviz_arg.value(context)
20+
use_velodyne = use_velodyne_arg.value(context)
1921

20-
xacro_path = get_file_path("panther_description", ["urdf"], "panther.urdf.xacro")
21-
xacro_arguments = {"use_sim": "true"}
22+
xacro_path = get_file_path("rcdt_panther", ["urdf"], "panther.urdf.xacro")
23+
components_path = get_file_path("rcdt_panther", ["config"], "components.yaml")
24+
xacro_arguments = {"use_sim": "true", "components_config_path": components_path}
25+
xacro_arguments["load_velodyne"] = "true" if use_velodyne else "false"
2226
robot_description = get_robot_description(xacro_path, xacro_arguments)
2327

2428
robot_state_publisher = Node(
@@ -41,7 +45,11 @@ def launch_setup(context: LaunchContext) -> None:
4145
joint_state_broadcaster = Node(
4246
package="controller_manager",
4347
executable="spawner",
44-
arguments=["joint_state_broadcaster"],
48+
arguments=[
49+
"joint_state_broadcaster",
50+
"-t",
51+
"joint_state_broadcaster/JointStateBroadcaster",
52+
],
4553
)
4654

4755
controllers = IncludeLaunchDescription(
@@ -87,6 +95,7 @@ def generate_launch_description() -> LaunchDescription:
8795
return LaunchDescription(
8896
[
8997
use_rviz_arg.declaration,
98+
use_velodyne_arg.declaration,
9099
OpaqueFunction(function=launch_setup),
91100
]
92101
)
Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<!--
3+
SPDX-FileCopyrightText: Alliander N. V.
4+
5+
SPDX-License-Identifier: Apache-2.0
6+
-->
7+
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="panther">
8+
9+
<!-- Set use_sim argument to let panther xacro load gazebo plugin: -->
10+
<xacro:arg name="use_sim" default="true" />
11+
12+
<!-- Load panther: -->
13+
<xacro:include filename="$(find panther_description)/urdf/panther_macro.urdf.xacro" ns="husarion" />
14+
<xacro:husarion.panther_robot
15+
panther_version="1.0"
16+
use_sim="$(arg use_sim)"
17+
wheel_config_file="$(find panther_description)/config/WH01.yaml"
18+
controller_config_file="$(find rcdt_panther)/config/ros_controller.yaml"
19+
battery_config_file="" />
20+
21+
<!-- Load Velodyne: -->
22+
<xacro:arg name="load_velodyne" default="false" />
23+
<xacro:if value="$(arg load_velodyne)">
24+
<xacro:include filename="$(find rcdt_sensors)/urdf/rcdt_velodyne.urdf.xacro" />
25+
<xacro:VLP-16>
26+
<origin xyz="0.18 0 0.03" rpy="0 0 0" />
27+
</xacro:VLP-16>
28+
</xacro:if>
29+
</robot>
Lines changed: 124 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,124 @@
1+
<?xml version='1.0' encoding='utf-8'?>
2+
<!--
3+
SPDX-FileCopyrightText: Alliander N. V.
4+
5+
SPDX-License-Identifier: Apache-2.0
6+
-->
7+
8+
<!--
9+
Based on:
10+
1.https://bitbucket.org/DataspeedInc/velodyne_simulator/src/master/velodyne_description/urdf/VLP-16.urdf.xacro
11+
2.https://github.com/husarion/ros_components_description/blob/ros2/urdf/velodyne_puck.urdf.xacro
12+
-->
13+
14+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="VLP-16">
15+
<xacro:property name="M_PI" value="3.1415926535897931" />
16+
<xacro:macro name="VLP-16"
17+
params="
18+
*origin
19+
parent:=cover_link
20+
name:=velodyne
21+
topic:=/velodyne_points
22+
update_rate:=10
23+
lasers:=16
24+
samples:=1875
25+
min_range:=0.3
26+
max_range:=130.0
27+
min_angle:=-${M_PI}
28+
max_angle:=${M_PI}
29+
">
30+
31+
<joint name="${name}_base_mount_joint" type="fixed">
32+
<xacro:insert_block name="origin" />
33+
<parent link="${parent}" />
34+
<child link="${name}_base_link" />
35+
</joint>
36+
37+
<link name="${name}_base_link">
38+
<inertial>
39+
<mass value="0.83" />
40+
<origin xyz="0 0 0.03585" />
41+
<inertia ixx="${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" ixy="0" ixz="0"
42+
iyy="${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" iyz="0"
43+
izz="${0.5 * 0.83 * (0.0516*0.0516)}" />
44+
</inertial>
45+
<visual>
46+
<geometry>
47+
<mesh filename="package://velodyne_description/meshes/VLP16_base_1.dae" />
48+
</geometry>
49+
</visual>
50+
<visual>
51+
<geometry>
52+
<mesh filename="package://velodyne_description/meshes/VLP16_base_2.dae" />
53+
</geometry>
54+
</visual>
55+
<collision>
56+
<origin rpy="0 0 0" xyz="0 0 0.03585" />
57+
<geometry>
58+
<cylinder radius="0.0516" length="0.0717" />
59+
</geometry>
60+
</collision>
61+
</link>
62+
63+
<joint name="${name}_base_scan_joint" type="fixed">
64+
<origin xyz="0 0 0.0377" rpy="0 0 0" />
65+
<parent link="${name}_base_link" />
66+
<child link="${name}_lidar" />
67+
</joint>
68+
69+
<link name="${name}_lidar">
70+
<inertial>
71+
<mass value="0.01" />
72+
<origin xyz="0 0 0" />
73+
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7" />
74+
</inertial>
75+
<visual>
76+
<origin xyz="0 0 -0.0377" />
77+
<geometry>
78+
<mesh filename="package://velodyne_description/meshes/VLP16_scan.dae" />
79+
</geometry>
80+
</visual>
81+
</link>
82+
83+
<gazebo reference="${name}_lidar">
84+
<sensor type="gpu_lidar" name="${name}">
85+
<always_on>true</always_on>
86+
<update_rate>${update_rate}</update_rate>
87+
88+
<topic>${topic}</topic>
89+
<visualize>false</visualize>
90+
91+
<ignition_frame_id>${name}_lidar</ignition_frame_id>
92+
<frame_id>${name}_lidar</frame_id>
93+
94+
<ray>
95+
<scan>
96+
<horizontal>
97+
<samples>${samples}</samples>
98+
<resolution>1</resolution>
99+
<min_angle>${min_angle}</min_angle>
100+
<max_angle>${max_angle}</max_angle>
101+
</horizontal>
102+
<vertical>
103+
<samples>${lasers}</samples>
104+
<resolution>1</resolution>
105+
<min_angle>-${15.0*M_PI/180.0}</min_angle>
106+
<max_angle> ${15.0*M_PI/180.0}</max_angle>
107+
</vertical>
108+
</scan>
109+
<range>
110+
<min>${min_range}</min>
111+
<max>${max_range}</max>
112+
<resolution>0.001</resolution>
113+
</range>
114+
<noise>
115+
<type>gaussian</type>
116+
<mean>0.0</mean>
117+
<stddev>0.0</stddev>
118+
</noise>
119+
</ray>
120+
</sensor>
121+
</gazebo>
122+
123+
</xacro:macro>
124+
</robot>

ros2_ws/src/rcdt_utilities/launch/gazebo_robot.launch.py

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,14 @@
1212
load_gazebo_ui_arg = LaunchArgument("load_gazebo_ui", False, [True, False])
1313
world_arg = LaunchArgument("world", "empty_camera.sdf")
1414
use_realsense_arg = LaunchArgument("realsense", False, [True, False])
15+
use_velodyne_arg = LaunchArgument("velodyne", False, [True, False])
1516

1617

1718
def launch_setup(context: LaunchContext) -> List:
1819
load_gazebo_ui = load_gazebo_ui_arg.value(context)
1920
world = world_arg.value(context)
2021
use_realsense = use_realsense_arg.value(context)
22+
use_velodyne = use_velodyne_arg.value(context)
2123

2224
sdf_file = get_file_path("rcdt_gz_worlds", ["worlds"], world)
2325
gz_args = f" -r {sdf_file}"
@@ -45,6 +47,12 @@ def launch_setup(context: LaunchContext) -> List:
4547
"/camera/camera/depth/image_rect_raw_float@sensor_msgs/msg/[email protected]",
4648
]
4749
)
50+
if use_velodyne:
51+
bridge_topics.extend(
52+
[
53+
"/velodyne_points/points@sensor_msgs/msg/[email protected]",
54+
]
55+
)
4856

4957
bridge = Node(
5058
package="ros_gz_bridge",
@@ -65,6 +73,7 @@ def generate_launch_description() -> LaunchDescription:
6573
load_gazebo_ui_arg.declaration,
6674
world_arg.declaration,
6775
use_realsense_arg.declaration,
76+
use_velodyne_arg.declaration,
6877
OpaqueFunction(function=launch_setup),
6978
]
7079
)

0 commit comments

Comments
 (0)