Skip to content

Commit 9e56d01

Browse files
committed
applying review suggestions
1 parent c425d16 commit 9e56d01

File tree

3 files changed

+4
-49
lines changed

3 files changed

+4
-49
lines changed

ros2_control_demo_robot/description/diffbot/diffbot.gazebo.xacro

Lines changed: 2 additions & 47 deletions
Original file line numberDiff line numberDiff line change
@@ -7,17 +7,9 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/diffbot_de
77

88
<xacro:macro name="diffbot_gazebo" params="prefix">
99

10-
<!-- ros_control plugin -->
11-
<gazebo>
12-
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
13-
<robotNamespace>/diffbot</robotNamespace>
14-
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
15-
</plugin>
16-
</gazebo>
17-
1810
<!-- Link1 -->
1911
<gazebo reference="${prefix}base_link">
20-
<material>Gazebo/Orange</material>
12+
<material>Gazebo/Blue</material>
2113
</gazebo>
2214

2315
<!-- Link2 -->
@@ -31,7 +23,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/diffbot_de
3123
<gazebo reference="${prefix}link2">
3224
<mu1>0.2</mu1>
3325
<mu2>0.2</mu2>
34-
<material>Gazebo/Orange</material>
26+
<material>Gazebo/Black</material>
3527
</gazebo>
3628

3729
<!-- camera_link -->
@@ -41,43 +33,6 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/diffbot_de
4133
<material>Gazebo/Red</material>
4234
</gazebo>
4335

44-
<!-- hokuyo -->
45-
<gazebo reference="${prefix}hokuyo_link">
46-
<sensor type="gpu_ray" name="head_hokuyo_sensor">
47-
<pose>0 0 0 0 0 0</pose>
48-
<visualize>false</visualize>
49-
<update_rate>40</update_rate>
50-
<ray>
51-
<scan>
52-
<horizontal>
53-
<samples>720</samples>
54-
<resolution>1</resolution>
55-
<min_angle>-1.570796</min_angle>
56-
<max_angle>1.570796</max_angle>
57-
</horizontal>
58-
</scan>
59-
<range>
60-
<min>0.10</min>
61-
<max>30.0</max>
62-
<resolution>0.01</resolution>
63-
</range>
64-
<noise>
65-
<type>gaussian</type>
66-
<!-- Noise parameters based on published spec for Hokuyo laser
67-
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
68-
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
69-
reading. -->
70-
<mean>0.0</mean>
71-
<stddev>0.01</stddev>
72-
</noise>
73-
</ray>
74-
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_gpu_laser.so">
75-
<topicName>/diffbot/laser/scan</topicName>
76-
<frameName>hokuyo_link</frameName>
77-
</plugin>
78-
</sensor>
79-
</gazebo>
80-
8136
<!-- camera -->
8237
<gazebo reference="${prefix}camera_link">
8338
<sensor type="camera" name="camera1">

ros2_control_demo_robot/description/diffbot_system.urdf.xacro

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<?xml version="1.0"?>
2-
<!-- Revolute-Revolute Manipulator -->
2+
<!-- Basic differential drive mobile base -->
33
<!--
44
Copied and modified from ROS1 example:
55
https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/diffbot_description/urdf/diffbot.xacro

ros2_control_demo_robot/launch/diffbot_system.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
# Copyright 2020 ROS2-Control Development Team (2020)
1+
# Copyright 2020 ros2_control Development Team
22
#
33
# Licensed under the Apache License, Version 2.0 (the "License");
44
# you may not use this file except in compliance with the License.

0 commit comments

Comments
 (0)