mirror of
https://github.com/vishweshvhavle/deep-rl-navigation.git
synced 2024-11-25 16:32:50 +08:00
Added training scripts
This commit is contained in:
parent
84d623a857
commit
dbf4a54040
60
DRL_robot_navigation_ros2/src/td3/CMakeLists.txt
Normal file
60
DRL_robot_navigation_ros2/src/td3/CMakeLists.txt
Normal file
@ -0,0 +1,60 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(td3)
|
||||
|
||||
# Default to C99
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
endif()
|
||||
|
||||
# Default to C++14
|
||||
if(NOT CMAKE_CXX_STANDARD)
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
endif()
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
# uncomment the following section in order to fill in
|
||||
# further dependencies manually.
|
||||
# find_package(<dependency> REQUIRED)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# uncomment the line when a copyright and license is not present in all source files
|
||||
#set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# uncomment the line when this package is not in a git repo
|
||||
#set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
install(
|
||||
DIRECTORY
|
||||
launch
|
||||
models
|
||||
scripts
|
||||
urdf
|
||||
worlds
|
||||
DESTINATION
|
||||
share/${PROJECT_NAME}/
|
||||
)
|
||||
|
||||
install(
|
||||
PROGRAMS
|
||||
scripts/replay_buffer.py
|
||||
scripts/test_velodyne_node.py
|
||||
scripts/train_velodyne_node.py
|
||||
scripts/point_cloud2.py
|
||||
launch/multi_robot_scenario.launch.py
|
||||
launch/robot_state_publisher.launch.py
|
||||
launch/training_simulation.launch.py
|
||||
launch/test_simulation.launch.py
|
||||
launch/pioneer3dx.rviz
|
||||
DESTINATION lib/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
ament_package()
|
@ -0,0 +1,37 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import IncludeLaunchDescription, ExecuteProcess
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
def generate_launch_description():
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
|
||||
world_file_name = 'td3.world'
|
||||
world = os.path.join(get_package_share_directory('td3'), 'worlds', world_file_name)
|
||||
launch_file_dir = os.path.join(get_package_share_directory('td3'), 'launch')
|
||||
pkg_gazebo_ros = get_package_share_directory('gazebo_ros')
|
||||
|
||||
return LaunchDescription([
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
|
||||
),
|
||||
launch_arguments={'world': world}.items(),
|
||||
),
|
||||
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
|
||||
),
|
||||
),
|
||||
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([launch_file_dir, '/robot_state_publisher.launch.py']),
|
||||
launch_arguments={'use_sim_time': use_sim_time}.items(),
|
||||
),
|
||||
])
|
354
DRL_robot_navigation_ros2/src/td3/launch/pioneer3dx.rviz
Normal file
354
DRL_robot_navigation_ros2/src/td3/launch/pioneer3dx.rviz
Normal file
@ -0,0 +1,354 @@
|
||||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 84
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1
|
||||
- /Camera1
|
||||
- /LaserScan1
|
||||
- /Odometry1
|
||||
- /Odometry1/Shape1
|
||||
- /MarkerArray1
|
||||
- /MarkerArray2
|
||||
- /MarkerArray3
|
||||
Splitter Ratio: 0.5286620259284973
|
||||
Tree Height: 449
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz_default_plugins/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz_default_plugins/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
battery0:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
cameraD:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
center_hubcap:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
center_wheel:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
chassis:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
front_camera:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
front_laser:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
left_hub:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
left_wheel:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
right_hub:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
right_wheel:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
sonar:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
swivel:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
top:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
velodyne:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
velodyne_base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Description Topic: /robot_description
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz_default_plugins/Camera
|
||||
Enabled: true
|
||||
Image Rendering: background and overlay
|
||||
Topic: /camera1/image_raw
|
||||
Name: Camera
|
||||
Overlay Alpha: 0.5
|
||||
Queue Size: 2
|
||||
Transport Hint: raw
|
||||
Unreliable: false
|
||||
Value: true
|
||||
Visibility:
|
||||
Grid: true
|
||||
LaserScan: true
|
||||
MarkerArray: true
|
||||
Odometry: true
|
||||
PointCloud2: true
|
||||
RobotModel: true
|
||||
Value: false
|
||||
Zoom Factor: 1
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 0.27687370777130127
|
||||
Min Value: 0.25088948011398315
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz_default_plugins/LaserScan
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: AxisColor
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Min Color: 0; 0; 0
|
||||
Name: LaserScan
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.10000000149011612
|
||||
Style: Flat Squares
|
||||
Topic: /front_laser/scan
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
- Angle Tolerance: 20
|
||||
Class: rviz_default_plugins/Odometry
|
||||
Covariance:
|
||||
Orientation:
|
||||
Alpha: 0.5
|
||||
Color: 255; 255; 127
|
||||
Color Style: Unique
|
||||
Frame: Local
|
||||
Offset: 1
|
||||
Scale: 1
|
||||
Value: true
|
||||
Position:
|
||||
Alpha: 0.30000001192092896
|
||||
Color: 204; 51; 204
|
||||
Scale: 1
|
||||
Value: true
|
||||
Value: false
|
||||
Enabled: true
|
||||
Keep: 100
|
||||
Name: Odometry
|
||||
Position Tolerance: 0.10000000149011612
|
||||
Queue Size: 10
|
||||
Shape:
|
||||
Alpha: 1
|
||||
Axes Length: 1
|
||||
Axes Radius: 0.10000000149011612
|
||||
Color: 255; 25; 0
|
||||
Head Length: 0.003000000026077032
|
||||
Head Radius: 0.004999999888241291
|
||||
Shaft Length: 0.05000000074505806
|
||||
Shaft Radius: 0.05000000074505806
|
||||
Value: Arrow
|
||||
Topic: /odom
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/MarkerArray
|
||||
Enabled: true
|
||||
Topic: /goal_point
|
||||
Name: MarkerArray
|
||||
Namespaces:
|
||||
"": true
|
||||
Queue Size: 100
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/MarkerArray
|
||||
Enabled: true
|
||||
Topic: /linear_velocity
|
||||
Name: MarkerArray
|
||||
Namespaces:
|
||||
"": true
|
||||
Queue Size: 100
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/MarkerArray
|
||||
Enabled: true
|
||||
Topic: /angular_velocity
|
||||
Name: MarkerArray
|
||||
Namespaces:
|
||||
"": true
|
||||
Queue Size: 100
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz_default_plugins/PointCloud2
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: Intensity
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Min Color: 0; 0; 0
|
||||
Name: PointCloud2
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.009999999776482582
|
||||
Style: Flat Squares
|
||||
Topic: /velodyne_points
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Default Light: true
|
||||
Fixed Frame: odom
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz_default_plugins/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz_default_plugins/MoveCamera
|
||||
- Class: rviz_default_plugins/Select
|
||||
- Class: rviz_default_plugins/FocusCamera
|
||||
- Class: rviz_default_plugins/Measure
|
||||
- Class: rviz_default_plugins/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz_default_plugins/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz_default_plugins/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Angle: 0.00500002596527338
|
||||
Class: rviz_default_plugins/TopDownOrtho
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Scale: 73.6252212524414
|
||||
Target Frame: <Fixed Frame>
|
||||
X: 0.048065461218357086
|
||||
Y: 0.11967461556196213
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Camera:
|
||||
collapsed: false
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1016
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000034bfc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000252000000c900fffffffb0000000a0049006d00610067006500000001eb000000ea0000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000295000000f30000001600fffffffb0000000c00430061006d00650072006100000002c2000000160000000000000000fb0000000a0049006d00610067006500000001bc000000770000000000000000fb0000000a0049006d00610067006500000002af000000e20000000000000000000000010000010f00000378fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000378000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000004dfc0100000002fb0000000800540069006d0065010000000000000738000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005c80000034b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: true
|
||||
Width: 1848
|
||||
X: 72
|
||||
Y: 27
|
@ -0,0 +1,40 @@
|
||||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='false')
|
||||
urdf_file_name = 'td_robot.urdf'
|
||||
|
||||
print('urdf_file_name : {}'.format(urdf_file_name))
|
||||
|
||||
urdf = os.path.join(
|
||||
get_package_share_directory('td3'),
|
||||
'urdf',
|
||||
urdf_file_name)
|
||||
|
||||
with open(urdf, 'r') as infp:
|
||||
robot_desc = infp.read()
|
||||
|
||||
return LaunchDescription([
|
||||
DeclareLaunchArgument(
|
||||
'use_sim_time',
|
||||
default_value='false',
|
||||
description='Use simulation (Gazebo) clock if true'),
|
||||
|
||||
Node(
|
||||
package='robot_state_publisher',
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
output='screen',
|
||||
parameters=[{
|
||||
'use_sim_time': use_sim_time,
|
||||
'robot_description': robot_desc,
|
||||
}],
|
||||
arguments=[urdf]),
|
||||
])
|
@ -0,0 +1,49 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
def generate_launch_description():
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
|
||||
world_file_name = 'td3.world'
|
||||
world = os.path.join(get_package_share_directory('td3'), 'worlds', world_file_name)
|
||||
launch_file_dir = os.path.join(get_package_share_directory('td3'), 'launch')
|
||||
pkg_gazebo_ros = get_package_share_directory('gazebo_ros')
|
||||
rviz_file = os.path.join(get_package_share_directory('td3'), 'launch', 'pioneer3dx.rviz')
|
||||
|
||||
return LaunchDescription([
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
|
||||
),
|
||||
launch_arguments={'world': world}.items(),
|
||||
),
|
||||
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
|
||||
),
|
||||
),
|
||||
|
||||
Node(package='td3',
|
||||
executable='test_velodyne_node.py',
|
||||
output='screen'
|
||||
),
|
||||
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([launch_file_dir, '/robot_state_publisher.launch.py']),
|
||||
launch_arguments={'use_sim_time': use_sim_time}.items(),
|
||||
),
|
||||
|
||||
Node(package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz2',
|
||||
arguments=['-d', rviz_file],
|
||||
output='screen'
|
||||
),
|
||||
])
|
@ -0,0 +1,49 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
def generate_launch_description():
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
|
||||
world_file_name = 'td3.world'
|
||||
world = os.path.join(get_package_share_directory('td3'), 'worlds', world_file_name)
|
||||
launch_file_dir = os.path.join(get_package_share_directory('td3'), 'launch')
|
||||
pkg_gazebo_ros = get_package_share_directory('gazebo_ros')
|
||||
rviz_file = os.path.join(get_package_share_directory('td3'), 'launch', 'pioneer3dx.rviz')
|
||||
|
||||
return LaunchDescription([
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
|
||||
),
|
||||
launch_arguments={'world': world}.items(),
|
||||
),
|
||||
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
|
||||
),
|
||||
),
|
||||
|
||||
Node(package='td3',
|
||||
executable='train_velodyne_node.py',
|
||||
output='screen'
|
||||
),
|
||||
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([launch_file_dir, '/robot_state_publisher.launch.py']),
|
||||
launch_arguments={'use_sim_time': use_sim_time}.items(),
|
||||
),
|
||||
|
||||
Node(package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz2',
|
||||
arguments=['-d', rviz_file],
|
||||
output='screen'
|
||||
),
|
||||
])
|
File diff suppressed because one or more lines are too long
@ -0,0 +1,20 @@
|
||||
=========================================
|
||||
Location Coordinates (x,y,z)
|
||||
=========================================
|
||||
|
||||
Chassis : -0.045 0 0.148
|
||||
Top : -0.045 0 0.234
|
||||
|
||||
Swivel : -0.185 0 0.055
|
||||
Center Hubcap : -0.211 0 0.037
|
||||
Center Wheel : -0.211 0 0.038
|
||||
|
||||
Right Hubcap : 0 0.158 0.091
|
||||
Right Wheel : 0 0.158 0.091
|
||||
|
||||
Left Hubcap : 0 -0.158 0.091
|
||||
Left Wheel : 0 -0.158 0.091
|
||||
|
||||
Front Sonar : -0.2 0 0.209
|
||||
Back Sonar : 0.109 0 0.209
|
||||
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -0,0 +1,16 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>td_robot</name>
|
||||
<version>2.0</version>
|
||||
<sdf version="1.7">td_robot.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>robot mania</name>
|
||||
<email>robo@robo.com</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
robot model
|
||||
</description>
|
||||
</model>
|
736
DRL_robot_navigation_ros2/src/td3/models/td_robot/td_robot.sdf
Normal file
736
DRL_robot_navigation_ros2/src/td3/models/td_robot/td_robot.sdf
Normal file
@ -0,0 +1,736 @@
|
||||
<sdf version='1.7'>
|
||||
<model name='td_robot'>
|
||||
<link name='base_link'>
|
||||
<inertial>
|
||||
<pose>-0.021738 0 0.059907 0 -0 0</pose>
|
||||
<mass>13.3401</mass>
|
||||
<inertia>
|
||||
<ixx>1.20926</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0.00863852</ixz>
|
||||
<iyy>1.32216</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1.23947</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='base_link_fixed_joint_lump__chassis_collision'>
|
||||
<pose>-0.045 0 0.148 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/chassis.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_link_fixed_joint_lump__cameraD_collision_1'>
|
||||
<pose>0.025 0 0.32 0 1.5708 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.1</length>
|
||||
<radius>0.03</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_link_fixed_joint_lump__front_camera_collision_2'>
|
||||
<pose>0.025 0 0.32 0 1.5708 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.1</length>
|
||||
<radius>0.03</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_link_fixed_joint_lump__front_laser_collision_3'>
|
||||
<pose>0.125 0 0.25 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.1 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_link_fixed_joint_lump__sonar_collision_4'>
|
||||
<pose>0.109 0 0.209 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_link_fixed_joint_lump__top_collision_5'>
|
||||
<pose>-0.045 0 0.234 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/top.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_link_fixed_joint_lump__velodyne_base_link_collision_6'>
|
||||
<pose>0.125 0 0.28585 0 -0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.0717</length>
|
||||
<radius>0.0516</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='base_link_fixed_joint_lump__chassis_visual_visual'>
|
||||
<pose>-0.045 0 0.148 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/chassis.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Red</name>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__battery0_visual_visual_1'>
|
||||
<pose>-0.14 0 0.13 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.151 0.065 0.094</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Black</name>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__cameraD_visual_2'>
|
||||
<pose>0.025 0 0.32 0 1.5708 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.1</length>
|
||||
<radius>0.03</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Grey</name>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__front_camera_visual_3'>
|
||||
<pose>0.025 0 0.32 0 1.5708 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.1</length>
|
||||
<radius>0.03</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Grey</name>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__front_laser_visual_4'>
|
||||
<pose>0.125 0 0.25 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/laser/hokuyo.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__front_sonar_vis_visual_5'>
|
||||
<pose>0.109 0 0.209 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/back_sonar.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__top_visual_6'>
|
||||
<pose>-0.045 0 0.234 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/top.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Black</name>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__velodyne_base_link_visual_7'>
|
||||
<pose>0.125 0 0.25 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/velodyne_description/meshes/VLP16_base_1.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__velodyne_base_link_visual_8'>
|
||||
<pose>0.125 0 0.25 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/velodyne_description/meshes/VLP16_base_2.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='base_link_fixed_joint_lump__velodyne_visual_9'>
|
||||
<pose>0.125 0 0.25 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/velodyne_description/meshes/VLP16_scan.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name='camera2' type='depth'>
|
||||
<update_rate>10</update_rate>
|
||||
<camera name='head'>
|
||||
<horizontal_fov>3.13</horizontal_fov>
|
||||
<image>
|
||||
<width>1024</width>
|
||||
<height>256</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>5</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0</mean>
|
||||
<stddev>0.007</stddev>
|
||||
</noise>
|
||||
</camera>
|
||||
<plugin name='camera_plugin' filename='libgazebo_ros_openni_kinect.so'>
|
||||
<baseline>0.2</baseline>
|
||||
<alwaysOn>1</alwaysOn>
|
||||
<updateRate>0.0</updateRate>
|
||||
<cameraName>camera_ir</cameraName>
|
||||
<imageTopicName>/camera/depth/image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>/camera/depth/camera_info</cameraInfoTopicName>
|
||||
<depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
|
||||
<depthImageInfoTopicName>/camera/depth/camera_info</depthImageInfoTopicName>
|
||||
<pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
|
||||
<frameName>camera_link</frameName>
|
||||
<pointCloudCutoff>0.05</pointCloudCutoff>
|
||||
<distortionK1>0</distortionK1>
|
||||
<distortionK2>0</distortionK2>
|
||||
<distortionK3>0</distortionK3>
|
||||
<distortionT1>0</distortionT1>
|
||||
<distortionT2>0</distortionT2>
|
||||
<CxPrime>0</CxPrime>
|
||||
<Cx>0</Cx>
|
||||
<Cy>0</Cy>
|
||||
<focalLength>0</focalLength>
|
||||
<hackBaseline>0</hackBaseline>
|
||||
</plugin>
|
||||
<pose>0.025 0 0.32 0 -0 0</pose>
|
||||
</sensor>
|
||||
<sensor name='camera1' type='camera'>
|
||||
<update_rate>30</update_rate>
|
||||
<camera name='head'>
|
||||
<horizontal_fov>1.92</horizontal_fov>
|
||||
<image>
|
||||
<width>512</width>
|
||||
<height>256</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>300</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0</mean>
|
||||
<stddev>0.007</stddev>
|
||||
</noise>
|
||||
</camera>
|
||||
<plugin name='camera_controller' filename='libgazebo_ros_camera.so'>
|
||||
<robotNamespace/>
|
||||
<alwaysOn>1</alwaysOn>
|
||||
<updateRate>0.0</updateRate>
|
||||
<cameraName>front_camera</cameraName>
|
||||
<imageTopicName>image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
||||
<frameName>front_camera</frameName>
|
||||
<hackBaseline>0.07</hackBaseline>
|
||||
<distortionK1>0.0</distortionK1>
|
||||
<distortionK2>0.0</distortionK2>
|
||||
<distortionK3>0.0</distortionK3>
|
||||
<distortionT1>0.0</distortionT1>
|
||||
<distortionT2>0.0</distortionT2>
|
||||
</plugin>
|
||||
<pose>0.025 0 0.32 0 -0 0</pose>
|
||||
</sensor>
|
||||
<sensor name='laser' type='ray'>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<resolution>1</resolution>
|
||||
<max_angle>1.5708</max_angle>
|
||||
<min_angle>-1.5708</min_angle>
|
||||
<samples>360</samples>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.08</min>
|
||||
<max>10</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
</ray>
|
||||
<plugin name='laser' filename='libgazebo_ros_ray_sensor.so'>
|
||||
<ros>
|
||||
<remapping>~/out:=/front_laser/scan</remapping>
|
||||
</ros>
|
||||
<output_type>sensor_msgs/LaserScan</output_type>
|
||||
<frame_name>front_laser</frame_name>
|
||||
</plugin>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>100</update_rate>
|
||||
<visualize>1</visualize>
|
||||
<pose>0.125 0 0.25 0 -0 0</pose>
|
||||
</sensor>
|
||||
<sensor name='velodyne-VLP16' type='ray'>
|
||||
<visualize>0</visualize>
|
||||
<update_rate>10</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>360</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-1.57</min_angle>
|
||||
<max_angle>1.57</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>16</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-0.261799</min_angle>
|
||||
<max_angle>0.261799</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.3</min>
|
||||
<max>131</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0</mean>
|
||||
<stddev>0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name='gazebo_ros_laser_controller' filename='libgazebo_ros_velodyne_laser.so'>
|
||||
<topicName>/velodyne_points</topicName>
|
||||
<frameName>velodyne</frameName>
|
||||
<min_range>0.1</min_range>
|
||||
<max_range>130.0</max_range>
|
||||
<gaussianNoise>0.008</gaussianNoise>
|
||||
</plugin>
|
||||
<pose>0.125 0 0.2877 0 -0 0</pose>
|
||||
</sensor>
|
||||
</link>
|
||||
<joint name='chassis_swivel_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>-0.185 0 0.055 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>swivel</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<effort>100</effort>
|
||||
<velocity>100</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='swivel'>
|
||||
<pose relative_to='chassis_swivel_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>0.01</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='swivel_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='swivel_fixed_joint_lump__base_visual_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/swivel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='swivel_wheel_joint' type='revolute'>
|
||||
<pose relative_to='swivel'>-0.026 0 -0.016 0 -0 0</pose>
|
||||
<parent>swivel</parent>
|
||||
<child>center_wheel</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<effort>100</effort>
|
||||
<velocity>100</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='center_wheel'>
|
||||
<pose relative_to='swivel_wheel_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.000318 0 -9.1e-05 0 -0 0</pose>
|
||||
<mass>0.11</mass>
|
||||
<inertia>
|
||||
<ixx>0.0248235</ixx>
|
||||
<ixy>-0.00142347</ixy>
|
||||
<ixz>0.00100543</ixz>
|
||||
<iyy>0.0304364</iyy>
|
||||
<iyz>-8.54693e-06</iyz>
|
||||
<izz>0.0235281</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='center_wheel_collision'>
|
||||
<pose>0 0 0 -1.5708 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.01</length>
|
||||
<radius>0.0375</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='center_wheel_fixed_joint_lump__center_hubcap_collision_1'>
|
||||
<pose>-0.0035 0 -0.001 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='center_wheel_fixed_joint_lump__base_visual_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/center_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='center_wheel_fixed_joint_lump__base_visual_visual_1'>
|
||||
<pose>-0.0035 0 -0.001 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/center_hubcap.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='left_hub_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>0 -0.15 0.09 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>left_hub</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='left_hub'>
|
||||
<pose relative_to='left_hub_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<mass>0.51</mass>
|
||||
<inertia>
|
||||
<ixx>0.0248235</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0304363</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.023528</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='left_hub_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='left_hub_fixed_joint_lump__left_wheel_collision_1'>
|
||||
<pose>0 0 0 -1.5708 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.01</length>
|
||||
<radius>0.09</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='left_hub_fixed_joint_lump__base_visual_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/left_hubcap.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='left_hub_fixed_joint_lump__base_visual_visual_1'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/left_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='right_hub_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>0 0.15 0.09 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>right_hub</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='right_hub'>
|
||||
<pose relative_to='right_hub_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<mass>0.51</mass>
|
||||
<inertia>
|
||||
<ixx>0.0248235</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0304363</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.023528</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='right_hub_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='right_hub_fixed_joint_lump__right_wheel_collision_1'>
|
||||
<pose>0 0 0 -1.5708 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.01</length>
|
||||
<radius>0.09</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='right_hub_fixed_joint_lump__base_visual_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/right_hubcap.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='right_hub_fixed_joint_lump__base_visual_visual_1'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://td_robot/meshes/p3dx/right_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<plugin name='differential_drive_controller' filename='libgazebo_ros_diff_drive.so'>
|
||||
|
||||
<robotNamespace/>
|
||||
<publish_odom>1</publish_odom>
|
||||
<publish_odom_tf>1</publish_odom_tf>
|
||||
<always_on>1</always_on>
|
||||
|
||||
<left_joint>left_hub_joint</left_joint>
|
||||
<right_joint>right_hub_joint</right_joint>
|
||||
|
||||
<wheel_separation>0.3</wheel_separation>
|
||||
<wheel_diameter>0.18</wheel_diameter>
|
||||
|
||||
<max_wheel_torque>20</max_wheel_torque>
|
||||
<max_wheel_acceleration>1.8</max_wheel_acceleration>
|
||||
<command_topic>cmd_vel</command_topic>
|
||||
|
||||
<odometry_topic>odom</odometry_topic>
|
||||
<odometry_frame>odom</odometry_frame>
|
||||
<odometrySource>world</odometrySource>
|
||||
|
||||
<robot_base_frame>base_link</robot_base_frame>
|
||||
<update_rate>50</update_rate>
|
||||
</plugin>
|
||||
|
||||
<static>0</static>
|
||||
|
||||
<plugin name='joint_state_publisher' filename='libgazebo_ros_joint_state_publisher.so'>
|
||||
<robotNamespace/>
|
||||
<joint_name>chassis_swivel_joint</joint_name>
|
||||
<joint_name>swivel_wheel_joint</joint_name>
|
||||
<joint_name>left_hub_joint</joint_name>
|
||||
<joint_name>right_hub_joint</joint_name>
|
||||
<update_rate>50.0</update_rate>
|
||||
<always_on>1</always_on>
|
||||
</plugin>
|
||||
|
||||
</model>
|
||||
</sdf>
|
@ -0,0 +1,47 @@
|
||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||
Changelog for package velodyne_description
|
||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
1.0.9 (2019-03-08)
|
||||
------------------
|
||||
|
||||
1.0.8 (2018-09-08)
|
||||
------------------
|
||||
|
||||
1.0.7 (2018-07-03)
|
||||
------------------
|
||||
* Added GPU support
|
||||
* Updated inertia tensors for VLP-16 and HDL-32E to realistic values
|
||||
* Removed unnecessary file extraction code in cmake
|
||||
* Contributors: Kevin Hallenbeck, Max Schwarz
|
||||
|
||||
1.0.6 (2017-10-17)
|
||||
------------------
|
||||
* Use robotNamespace as prefix for PointCloud2 topic frame_id by default
|
||||
* Contributors: Micho Radovnikovich
|
||||
|
||||
1.0.5 (2017-09-05)
|
||||
------------------
|
||||
* Increased minimum collision range to prevent self-clipping when in motion
|
||||
* Added many URDF parameters, and set example sample count to reasonable values
|
||||
* Launch rviz with gazebo
|
||||
* Contributors: Kevin Hallenbeck
|
||||
|
||||
1.0.4 (2017-04-24)
|
||||
------------------
|
||||
* Updated package.xml format to version 2
|
||||
* Contributors: Kevin Hallenbeck
|
||||
|
||||
1.0.3 (2016-08-13)
|
||||
------------------
|
||||
* Contributors: Kevin Hallenbeck
|
||||
|
||||
1.0.2 (2016-02-03)
|
||||
------------------
|
||||
* Moved M_PI property out of macro to support multiple instances
|
||||
* Materials caused problems with more than one sensors. Removed.
|
||||
* Added example urdf and gazebo
|
||||
* Changed to DAE meshes
|
||||
* Added meshes. Added HDL-32E.
|
||||
* Start from block laser
|
||||
* Contributors: Kevin Hallenbeck
|
@ -0,0 +1,34 @@
|
||||
cmake_minimum_required(VERSION 3.5.0)
|
||||
project(velodyne_description)
|
||||
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(gazebo REQUIRED)
|
||||
find_package(gazebo_ros_pkgs REQUIRED)
|
||||
|
||||
ament_export_dependencies(gazebo_ros_pkgs)
|
||||
|
||||
ament_package()
|
||||
|
||||
install(DIRECTORY launch/
|
||||
DESTINATION share/${PROJECT_NAME}/launch
|
||||
)
|
||||
|
||||
install(DIRECTORY meshes/
|
||||
DESTINATION share/${PROJECT_NAME}/meshes
|
||||
)
|
||||
|
||||
install(DIRECTORY rviz/
|
||||
DESTINATION share/${PROJECT_NAME}/rviz
|
||||
)
|
||||
|
||||
install(DIRECTORY urdf/
|
||||
DESTINATION share/${PROJECT_NAME}/urdf
|
||||
)
|
||||
|
||||
install(DIRECTORY world/
|
||||
DESTINATION share/${PROJECT_NAME}/world
|
||||
)
|
||||
|
||||
install(DIRECTORY models/
|
||||
DESTINATION share/${PROJECT_NAME}/models
|
||||
)
|
@ -0,0 +1,103 @@
|
||||
#*********************************************************************
|
||||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2019, Open Source Robotics Foundation, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Dataspeed Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#********************************************************************
|
||||
|
||||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
import ament_index_python.packages
|
||||
import launch
|
||||
import launch_ros.actions
|
||||
import subprocess
|
||||
|
||||
def read_file(path):
|
||||
with open(path, 'r') as f:
|
||||
contents = f.read()
|
||||
return contents
|
||||
|
||||
def generate_launch_description():
|
||||
output_mode = 'both'
|
||||
gpu = False;
|
||||
|
||||
gazebo_dir = os.path.dirname(get_package_share_directory('velodyne_description'))
|
||||
world = os.path.join(get_package_share_directory('velodyne_description'), 'world', 'lio_sam.model')
|
||||
urdf_dir = os.path.join(get_package_share_directory('velodyne_description'),'urdf')
|
||||
xacro_urdf = os.path.join(urdf_dir, 'example.urdf.xacro')
|
||||
robot_urdf = os.path.join(urdf_dir, 'example.urdf')
|
||||
xacro_proc = subprocess.Popen("xacro {0} gpu:={1} > {2}".format(xacro_urdf, gpu, robot_urdf) ,
|
||||
stdout=subprocess.PIPE, stderr=subprocess.STDOUT, shell=True)
|
||||
xacro_proc.wait()
|
||||
assert os.path.exists(robot_urdf)
|
||||
urdf_contents = read_file(robot_urdf)
|
||||
|
||||
rviz_config = os.path.join(
|
||||
ament_index_python.packages.get_package_share_directory('velodyne_description'),
|
||||
'rviz', 'example.rviz')
|
||||
|
||||
rsp = launch_ros.actions.Node(package='robot_state_publisher',
|
||||
node_executable='robot_state_publisher',
|
||||
output='both',
|
||||
arguments=[robot_urdf])
|
||||
|
||||
rviz = launch_ros.actions.Node(package='rviz2',
|
||||
node_executable='rviz2',
|
||||
output='both',
|
||||
arguments=['-d', rviz_config])
|
||||
|
||||
spawn_entity_message_contents = "'{initial_pose:{ position: {x: 0, y: 0, z: 0}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}}, name: \"velodyne_description\", xml: \"" + urdf_contents.replace('"', '\\"') + "\"}'"
|
||||
spawn_entity = launch.actions.ExecuteProcess(
|
||||
name='spawn_entity', cmd=['ros2', 'service', 'call', '/spawn_entity', 'gazebo_msgs/SpawnEntity', spawn_entity_message_contents], env=os.environ.copy(), output=output_mode, shell=True, log_cmd=False)
|
||||
|
||||
# Publishes the URDF to /robot_description.
|
||||
# This is a workaround to make rviz get the urdf.
|
||||
urdf_pub_data = urdf_contents.replace('"', '\\"')
|
||||
launch_urdf = launch.actions.ExecuteProcess(
|
||||
name='launch_urdf', cmd=['ros2', 'topic', 'pub', '-r', '0.1', '/robot_description', 'std_msgs/String', '\'data: "' + urdf_pub_data + '"\''], env=os.environ.copy(), output=output_mode, shell=True, log_cmd=False)
|
||||
|
||||
my_env = os.environ.copy()
|
||||
my_env["GAZEBO_MODEL_PATH"] = gazebo_dir
|
||||
gazebo = launch.actions.ExecuteProcess(
|
||||
name='gazebo', cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so', world], env=my_env, output=output_mode, shell=True, log_cmd=False)
|
||||
|
||||
return launch.LaunchDescription([rsp,
|
||||
rviz,
|
||||
gazebo,
|
||||
spawn_entity,
|
||||
launch_urdf,
|
||||
launch.actions.RegisterEventHandler(
|
||||
event_handler=launch.event_handlers.OnProcessExit(
|
||||
target_action=gazebo,
|
||||
on_exit=[launch.actions.EmitEvent(
|
||||
event=launch.events.Shutdown())],
|
||||
)),
|
||||
])
|
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 5.7 KiB |
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 14 KiB |
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 23 KiB |
File diff suppressed because one or more lines are too long
Binary file not shown.
After Width: | Height: | Size: 13 KiB |
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because it is too large
Load Diff
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
Binary file not shown.
Binary file not shown.
@ -0,0 +1,16 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>rs_robot</name>
|
||||
<version>2.0</version>
|
||||
<sdf version="1.7">rs_robot.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>robot mania</name>
|
||||
<email>robo@robo.com</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
robot model
|
||||
</description>
|
||||
</model>
|
@ -0,0 +1,633 @@
|
||||
<sdf version='1.7'>
|
||||
<model name='rs_robot'>
|
||||
|
||||
<link name="base_footprint"/>
|
||||
|
||||
<link name='base_link'>
|
||||
<inertial>
|
||||
<pose>-0.003143 0 0.022 0 -0 0</pose>
|
||||
<mass>1.4</mass>
|
||||
<inertia>
|
||||
<ixx>0.0004846</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0.000132</ixz>
|
||||
<iyy>0.000352971</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.000339571</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='base_footprint_fixed_joint_lump__base_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/base/base_link.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base_footprint_fixed_joint_lump__lidar_base_link_collision_1'>
|
||||
<pose>-0.022 0 0.035 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/lidar_base/YDlidar_base.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='base_footprint_fixed_joint_lump__base_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/base/base_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='base_footprint_fixed_joint_lump__lidar_base_link_visual_1'>
|
||||
<pose>-0.022 0 0.035 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/lidar_base/YDlidar_base.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name="hls_lfcd_lds" type="ray">
|
||||
<always_on>true</always_on>
|
||||
<visualize>false</visualize>
|
||||
<pose>-0.2 0 0.27 0 0 0</pose>
|
||||
<update_rate>40</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>720</samples>
|
||||
<resolution>1.000000</resolution>
|
||||
<min_angle>-3.14158</min_angle>
|
||||
<max_angle>3.14158</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.120000</min>
|
||||
<max>20</max>
|
||||
<resolution>0.015000</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.01</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
|
||||
<ros>
|
||||
<remapping>~/out:=scan</remapping>
|
||||
</ros>
|
||||
<output_type>sensor_msgs/LaserScan</output_type>
|
||||
<frame_name>base_scan</frame_name>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</link>
|
||||
<joint name='front_left_steering_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>0.077 0.031 -0.004 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>front_left_steering_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.1</lower>
|
||||
<upper>2.1</upper>
|
||||
<effort>5</effort>
|
||||
<velocity>6.28</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='front_left_steering_link'>
|
||||
<pose relative_to='front_left_steering_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 -0.02 0 -0 0</pose>
|
||||
<mass>0.15</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4e-06</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='front_left_steering_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/suspension/sus_link.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='front_left_steering_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/suspension/front_left_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
<joint name='ffl_wheel_joint' type='revolute'>
|
||||
<pose relative_to='front_left_steering_link'>0 0.021 -0.025 0 0 -3.14159</pose>
|
||||
<parent>front_left_steering_link</parent>
|
||||
<child>ffl_wheel_link</child>
|
||||
<axis>
|
||||
<xyz>0 -1 0</xyz>
|
||||
<limit>
|
||||
<effort>1.5</effort>
|
||||
<velocity>20</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='ffl_wheel_link'>
|
||||
<pose relative_to='ffl_wheel_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 -0.007 0 0 -0 0</pose>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.8e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='ffl_wheel_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/wheel/robot_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='ffl_wheel_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/wheel/wheel_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='front_right_steering_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>0.077 -0.031 -0.004 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>front_right_steering_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.1</lower>
|
||||
<upper>2.1</upper>
|
||||
<effort>5</effort>
|
||||
<velocity>6.28</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='front_right_steering_link'>
|
||||
<pose relative_to='front_right_steering_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 -0.02 0 -0 0</pose>
|
||||
<mass>0.15</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4e-06</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='front_right_steering_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/suspension/sus_link.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='front_right_steering_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/suspension/front_right_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
<joint name='ffr_wheel_joint' type='revolute'>
|
||||
<pose relative_to='front_right_steering_link'>0 -0.021 -0.025 0 -0 0</pose>
|
||||
<parent>front_right_steering_link</parent>
|
||||
<child>ffr_wheel_link</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<effort>1.5</effort>
|
||||
<velocity>20</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='ffr_wheel_link'>
|
||||
<pose relative_to='ffr_wheel_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 -0.007 0 0 -0 0</pose>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.8e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='ffr_wheel_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/wheel/robot_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='ffr_wheel_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/wheel/wheel_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lidar_head_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>0 0 0.035 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>lidar_head_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<effort>1.5</effort>
|
||||
<velocity>20</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lidar_head_link'>
|
||||
<pose relative_to='lidar_head_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.8e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lidar_head_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/lidar_head/YDlidar_head.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='lidar_head_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/lidar_head/YDlidar_head.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
<joint name='rear_left_steering_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>-0.077 0.031 -0.004 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>rear_left_steering_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.1</lower>
|
||||
<upper>2.1</upper>
|
||||
<effort>5</effort>
|
||||
<velocity>6.28</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rear_left_steering_link'>
|
||||
<pose relative_to='rear_left_steering_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 -0.02 0 -0 0</pose>
|
||||
<mass>0.15</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4e-06</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rear_left_steering_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/suspension/sus_link.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='rear_left_steering_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/suspension/rear_left_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
<joint name='rfl_wheel_joint' type='revolute'>
|
||||
<pose relative_to='rear_left_steering_link'>0 0.021 -0.025 0 0 -3.14159</pose>
|
||||
<parent>rear_left_steering_link</parent>
|
||||
<child>rfl_wheel_link</child>
|
||||
<axis>
|
||||
<xyz>0 -1 0</xyz>
|
||||
<limit>
|
||||
<effort>1.5</effort>
|
||||
<velocity>20</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rfl_wheel_link'>
|
||||
<pose relative_to='rfl_wheel_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 -0.007 0 0 -0 0</pose>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.8e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rfl_wheel_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/wheel/robot_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rfl_wheel_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/wheel/wheel_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rear_right_steering_joint' type='revolute'>
|
||||
<pose relative_to='base_link'>-0.077 -0.031 -0.004 0 -0 0</pose>
|
||||
<parent>base_link</parent>
|
||||
<child>rear_right_steering_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.1</lower>
|
||||
<upper>2.1</upper>
|
||||
<effort>5</effort>
|
||||
<velocity>6.28</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rear_right_steering_link'>
|
||||
<pose relative_to='rear_right_steering_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 -0.02 0 -0 0</pose>
|
||||
<mass>0.15</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4e-06</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rear_right_steering_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/suspension/sus_link.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>0.05</mu>
|
||||
<mu2>0.05</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='rear_right_steering_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/suspension/rear_right_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
<joint name='rfr_wheel_joint' type='revolute'>
|
||||
<pose relative_to='rear_right_steering_link'>0 -0.021 -0.025 0 -0 0</pose>
|
||||
<parent>rear_right_steering_link</parent>
|
||||
<child>rfr_wheel_link</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<effort>1.5</effort>
|
||||
<velocity>20</velocity>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rfr_wheel_link'>
|
||||
<pose relative_to='rfr_wheel_joint'>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 -0.007 0 0 -0 0</pose>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>1e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.8e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rfr_wheel_link_collision'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/STL/wheel/robot_wheel.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rfr_wheel_link_visual'>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rs_robot/meshes/DAE/wheel/wheel_link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<static>0</static>
|
||||
<plugin name='gazebo_ros_control' filename='libgazebo_ros_control.so'/>
|
||||
</model>
|
||||
</sdf>
|
@ -0,0 +1,28 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>velodyne_description</name>
|
||||
<version>1.0.9</version>
|
||||
<description>
|
||||
URDF and meshes describing Velodyne laser scanners.
|
||||
</description>
|
||||
|
||||
<license>BSD</license>
|
||||
<author>Kevin Hallenbeck</author>
|
||||
<maintainer email="khallenbeck@dataspeedinc.com">Kevin Hallenbeck</maintainer>
|
||||
<url type="website">http://wiki.ros.org/velodyne_description</url>
|
||||
<url type="repository">https://bitbucket.org/dataspeedinc/velodyne_simulator</url>
|
||||
<url type="bugtracker">https://bitbucket.org/dataspeedinc/velodyne_simulator/issues</url>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>gazebo_ros_pkgs</depend>
|
||||
|
||||
<exec_depend>urdf</exec_depend>
|
||||
<exec_depend>xacro</exec_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
<gazebo_ros gazebo_model_path="${prefix}/models"/>
|
||||
</export>
|
||||
|
||||
</package>
|
@ -0,0 +1,186 @@
|
||||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1
|
||||
- /PointCloud21
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 623
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
Expanded:
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz_default_plugins/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz_default_plugins/RobotModel
|
||||
Collision Enabled: false
|
||||
Description File: ""
|
||||
Description Source: Topic
|
||||
Description Topic: /robot_description
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
base_footprint:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
velodyne:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
velodyne2:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
velodyne2_base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
velodyne_base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
TF Prefix: ""
|
||||
Unreliable: false
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz_default_plugins/PointCloud2
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: Intensity
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 0
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: PointCloud2
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.009999999776482582
|
||||
Style: Flat Squares
|
||||
Topic: /velodyne_points2
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: base_link
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz_default_plugins/MoveCamera
|
||||
- Class: rviz_default_plugins/Select
|
||||
- Class: rviz_default_plugins/FocusCamera
|
||||
- Class: rviz_default_plugins/Measure
|
||||
Line color: 128; 128; 0
|
||||
- Class: rviz_default_plugins/SetInitialPose
|
||||
Topic: /initialpose
|
||||
- Class: rviz_default_plugins/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz_default_plugins/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Transformation:
|
||||
Current:
|
||||
Class: rviz_default_plugins/TF
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 3.977553606033325
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.21539804339408875
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.665398120880127
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 846
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd000000040000000000000156000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000023f000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1200
|
||||
X: 60
|
||||
Y: 60
|
@ -0,0 +1,138 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="HDL-32E">
|
||||
<xacro:property name="M_PI" value="3.1415926535897931" />
|
||||
<xacro:macro name="HDL-32E" params="*origin parent:=base_link name:=velodyne topic:=/velodyne_points hz:=10 lasers:=32 samples:=2187 collision_range:=0.3 min_range:=0.9 max_range:=130.0 noise:=0.008 min_angle:=-${M_PI} max_angle:=${M_PI} gpu:=false">
|
||||
|
||||
<joint name="${name}_base_mount_joint" type="fixed">
|
||||
<xacro:insert_block name="origin" />
|
||||
<parent link="${parent}"/>
|
||||
<child link="${name}_base_link"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_base_link">
|
||||
<inertial>
|
||||
<mass value="1.0"/>
|
||||
<origin xyz="0 0 0.07212"/>
|
||||
<inertia ixx="${(1.0 * (3.0*0.04267*0.04267 + 0.14424*0.14424)) / 12.0}" ixy="0" ixz="0"
|
||||
iyy="${(1.0 * (3.0*0.04267*0.04267 + 0.14424*0.14424)) / 12.0}" iyz="0"
|
||||
izz="${0.5 * 1.0 * (0.04267*0.04267)}"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/HDL32E_base.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.07212"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.04267" length="0.14424"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_base_scan_joint" type="fixed" >
|
||||
<origin xyz="0 0 0.09081" rpy="0 0 0" />
|
||||
<parent link="${name}_base_link" />
|
||||
<child link="${name}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}">
|
||||
<inertial>
|
||||
<mass value="0.01"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 -0.09081" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/HDL32E_scan.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<!-- Gazebo requires the velodyne_gazebo_plugins package -->
|
||||
<gazebo reference="${name}">
|
||||
<xacro:if value="${gpu}">
|
||||
<sensor type="gpu_ray" name="${name}-HDL32E">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>${hz}</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>${samples}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${min_angle}</min_angle>
|
||||
<max_angle>${max_angle}</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>${lasers}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-${30.67*M_PI/180.0}</min_angle>
|
||||
<max_angle> ${10.67*M_PI/180.0}</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${collision_range}</min>
|
||||
<max>${max_range+1}</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
|
||||
<topicName>${topic}</topicName>
|
||||
<frameName>${name}</frameName>
|
||||
<min_range>${min_range}</min_range>
|
||||
<max_range>${max_range}</max_range>
|
||||
<gaussianNoise>${noise}</gaussianNoise>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</xacro:if>
|
||||
<xacro:unless value="${gpu}">
|
||||
<sensor type="ray" name="${name}-HDL32E">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>${hz}</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>${samples}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${min_angle}</min_angle>
|
||||
<max_angle>${max_angle}</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>${lasers}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-${30.67*M_PI/180.0}</min_angle>
|
||||
<max_angle> ${10.67*M_PI/180.0}</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${collision_range}</min>
|
||||
<max>${max_range+1}</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
|
||||
<topicName>${topic}</topicName>
|
||||
<frameName>${name}</frameName>
|
||||
<min_range>${min_range}</min_range>
|
||||
<max_range>${max_range}</max_range>
|
||||
<gaussianNoise>${noise}</gaussianNoise>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</xacro:unless>
|
||||
</gazebo>
|
||||
|
||||
</xacro:macro>
|
||||
</robot>
|
@ -0,0 +1,143 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="VLP-16">
|
||||
<xacro:property name="M_PI" value="3.1415926535897931"/>
|
||||
<xacro:macro name="VLP-16" params="*origin parent:=base_link name:=velodyne topic:=/velodyne_points hz:=10 lasers:=16 samples:=1875 collision_range:=0.3 min_range:=0.9 max_range:=130.0 noise:=0.008 min_angle:=-${M_PI} max_angle:=${M_PI} gpu:=false">
|
||||
|
||||
<joint name="${name}_base_mount_joint" type="fixed">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<parent link="${parent}"/>
|
||||
<child link="${name}_base_link"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_base_link">
|
||||
<inertial>
|
||||
<mass value="0.83"/>
|
||||
<origin xyz="0 0 0.03585"/>
|
||||
<inertia ixx="${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" ixy="0" ixz="0" iyy="${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" iyz="0" izz="${0.5 * 0.83 * (0.0516*0.0516)}"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/VLP16_base_1.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/VLP16_base_2.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.03585"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.0516" length="0.0717"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_base_scan_joint" type="fixed">
|
||||
<origin xyz="0 0 0.0377" rpy="0 0 0"/>
|
||||
<parent link="${name}_base_link"/>
|
||||
<child link="${name}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}">
|
||||
<inertial>
|
||||
<mass value="0.01"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 -0.0377"/>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/VLP16_scan.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<!-- Gazebo requires the velodyne_gazebo_plugins package -->
|
||||
<gazebo reference="${name}">
|
||||
<xacro:if value="${gpu}">
|
||||
<sensor type="gpu_ray" name="${name}-VLP16">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>${hz}</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>${samples}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${min_angle}</min_angle>
|
||||
<max_angle>${max_angle}</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>${lasers}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-${15.0*M_PI/180.0}</min_angle>
|
||||
<max_angle>
|
||||
${15.0*M_PI/180.0}</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${collision_range}</min>
|
||||
<max>${max_range+1}</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
|
||||
<topicName>${topic}</topicName>
|
||||
<frameName>${name}</frameName>
|
||||
<min_range>${min_range}</min_range>
|
||||
<max_range>${max_range}</max_range>
|
||||
<gaussianNoise>${noise}</gaussianNoise>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</xacro:if>
|
||||
<xacro:unless value="${gpu}">
|
||||
<sensor type="ray" name="${name}-VLP16">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>${hz}</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>${samples}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${min_angle}</min_angle>
|
||||
<max_angle>${max_angle}</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>${lasers}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-${15.0*M_PI/180.0}</min_angle>
|
||||
<max_angle>
|
||||
${15.0*M_PI/180.0}</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${collision_range}</min>
|
||||
<max>${max_range+1}</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
|
||||
<topicName>${topic}</topicName>
|
||||
<frameName>${name}</frameName>
|
||||
<min_range>${min_range}</min_range>
|
||||
<max_range>${max_range}</max_range>
|
||||
<gaussianNoise>${noise}</gaussianNoise>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</xacro:unless>
|
||||
</gazebo>
|
||||
|
||||
</xacro:macro>
|
||||
</robot>
|
@ -0,0 +1,170 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="VLP-32C">
|
||||
<xacro:property name="M_PI" value="3.1415926535897931"/>
|
||||
<xacro:macro name="VLP-32C" params="*origin parent:=base_link name:=velodyne topic:=/velodyne_points hz:=10 lasers:=32 samples:=1200 collision_range:=0.3 min_range:=0.4 max_range:=200.0 noise:=0.008 min_angle:=-${M_PI} max_angle:=${M_PI} gpu:=false">
|
||||
|
||||
<joint name="${name}_base_mount_joint" type="fixed">
|
||||
<xacro:insert_block name="origin"/>
|
||||
<parent link="${parent}"/>
|
||||
<child link="${name}_base_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- TODO(hidmic) update physical model, Velodyne Lidar provides mechanical drawings for VLP-32C but no meshes. -->
|
||||
<link name="${name}_base_link">
|
||||
<inertial>
|
||||
<mass value="0.83"/>
|
||||
<origin xyz="0 0 0.03585"/>
|
||||
<inertia ixx="${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" ixy="0" ixz="0" iyy="${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" iyz="0" izz="${0.5 * 0.83 * (0.0516*0.0516)}"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/VLP16_base_1.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/VLP16_base_2.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.03585"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.0516" length="0.0717"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_base_scan_joint" type="fixed">
|
||||
<origin xyz="0 0 0.0377" rpy="0 0 0"/>
|
||||
<parent link="${name}_base_link"/>
|
||||
<child link="${name}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}">
|
||||
<inertial>
|
||||
<mass value="0.01"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 -0.0377"/>
|
||||
<geometry>
|
||||
<mesh filename="package://velodyne_description/meshes/VLP16_scan.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<!-- Gazebo requires the velodyne_gazebo_plugins package -->
|
||||
<gazebo reference="${name}">
|
||||
<xacro:if value="${gpu}">
|
||||
<sensor type="gpu_ray" name="${name}-VLP32C">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>${hz}</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>${samples}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${min_angle}</min_angle>
|
||||
<max_angle>${max_angle}</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>${2 * lasers}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${-25.0*M_PI/180.0}</min_angle>
|
||||
<max_angle>${15.0*M_PI/180.0}</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${collision_range}</min>
|
||||
<max>${max_range+1}</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
|
||||
<topicName>${topic}</topicName>
|
||||
<frameName>${name}</frameName>
|
||||
<scan>
|
||||
<vertical>
|
||||
<angles>
|
||||
${-25.000 * M_PI / 180.0} ${-15.639 * M_PI / 180.0} ${-11.310 * M_PI / 180.0} ${-8.843 * M_PI / 180.0}
|
||||
${ -7.254 * M_PI / 180.0} ${ -6.148 * M_PI / 180.0} ${ -5.333 * M_PI / 180.0} ${-4.667 * M_PI / 180.0}
|
||||
${ -4.000 * M_PI / 180.0} ${ -3.667 * M_PI / 180.0} ${ -3.333 * M_PI / 180.0} ${-3.000 * M_PI / 180.0}
|
||||
${ -2.667 * M_PI / 180.0} ${ -2.333 * M_PI / 180.0} ${ -2.000 * M_PI / 180.0} ${-1.667 * M_PI / 180.0}
|
||||
${ -1.333 * M_PI / 180.0} ${ -1.000 * M_PI / 180.0} ${ -0.667 * M_PI / 180.0} ${-0.333 * M_PI / 180.0}
|
||||
${ 0.000 * M_PI / 180.0} ${ 0.333 * M_PI / 180.0} ${ 0.667 * M_PI / 180.0} ${ 1.000 * M_PI / 180.0}
|
||||
${ 1.333 * M_PI / 180.0} ${ 1.667 * M_PI / 180.0} ${ 2.333 * M_PI / 180.0} ${ 3.333 * M_PI / 180.0}
|
||||
${ 4.667 * M_PI / 180.0} ${ 7.000 * M_PI / 180.0} ${ 10.333 * M_PI / 180.0} ${15.000 * M_PI / 180.0}
|
||||
</angles>
|
||||
</vertical>
|
||||
</scan>
|
||||
<min_range>${min_range}</min_range>
|
||||
<max_range>${max_range}</max_range>
|
||||
<gaussianNoise>${noise}</gaussianNoise>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</xacro:if>
|
||||
<xacro:unless value="${gpu}">
|
||||
<sensor type="ray" name="${name}-VLP32C">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>${hz}</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>${samples}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${min_angle}</min_angle>
|
||||
<max_angle>${max_angle}</max_angle>
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>${lasers}</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>${-25.0*M_PI/180.0}</min_angle>
|
||||
<max_angle>${15.0*M_PI/180.0}</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${collision_range}</min>
|
||||
<max>${max_range+1}</max>
|
||||
<resolution>0.001</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.0</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
|
||||
<topicName>${topic}</topicName>
|
||||
<frameName>${name}</frameName>
|
||||
<scan>
|
||||
<vertical>
|
||||
<angles>
|
||||
${-25.000 * M_PI / 180.0} ${-15.639 * M_PI / 180.0} ${-11.310 * M_PI / 180.0} ${-8.843 * M_PI / 180.0}
|
||||
${ -7.254 * M_PI / 180.0} ${ -6.148 * M_PI / 180.0} ${ -5.333 * M_PI / 180.0} ${-4.667 * M_PI / 180.0}
|
||||
${ -4.000 * M_PI / 180.0} ${ -3.667 * M_PI / 180.0} ${ -3.333 * M_PI / 180.0} ${-3.000 * M_PI / 180.0}
|
||||
${ -2.667 * M_PI / 180.0} ${ -2.333 * M_PI / 180.0} ${ -2.000 * M_PI / 180.0} ${-1.667 * M_PI / 180.0}
|
||||
${ -1.333 * M_PI / 180.0} ${ -1.000 * M_PI / 180.0} ${ -0.667 * M_PI / 180.0} ${-0.333 * M_PI / 180.0}
|
||||
${ 0.000 * M_PI / 180.0} ${ 0.333 * M_PI / 180.0} ${ 0.667 * M_PI / 180.0} ${ 1.000 * M_PI / 180.0}
|
||||
${ 1.333 * M_PI / 180.0} ${ 1.667 * M_PI / 180.0} ${ 2.333 * M_PI / 180.0} ${ 3.333 * M_PI / 180.0}
|
||||
${ 4.667 * M_PI / 180.0} ${ 7.000 * M_PI / 180.0} ${ 10.333 * M_PI / 180.0} ${15.000 * M_PI / 180.0}
|
||||
</angles>
|
||||
</vertical>
|
||||
</scan>
|
||||
<min_range>${min_range}</min_range>
|
||||
<max_range>${max_range}</max_range>
|
||||
<gaussianNoise>${noise}</gaussianNoise>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</xacro:unless>
|
||||
</gazebo>
|
||||
|
||||
</xacro:macro>
|
||||
</robot>
|
@ -0,0 +1,50 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="example">
|
||||
<xacro:arg name="gpu" default="false"/>
|
||||
<xacro:property name="gpu" value="$(arg gpu)" />
|
||||
|
||||
<!-- Base Footprint -->
|
||||
<link name="base_footprint" />
|
||||
|
||||
<!-- Base Link -->
|
||||
<joint name="footprint" type="fixed" >
|
||||
<parent link="base_footprint" />
|
||||
<child link="base_link" />
|
||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
||||
</joint>
|
||||
<link name="base_link" >
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.5 0.5 0.1" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.5 0.5 0.1" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0"/>
|
||||
<mass value="10"/>
|
||||
<inertia ixx="3.0" ixy="0.0" ixz="0.0"
|
||||
iyy="3.0" iyz="0.0"
|
||||
izz="3.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/>
|
||||
<VLP-16 parent="base_link" name="velodyne" topic="/velodyne_points" hz="10" samples="440" gpu="${gpu}">
|
||||
<origin xyz="0 0 0.4" rpy="0 0 0" />
|
||||
</VLP-16>
|
||||
|
||||
<xacro:include filename="$(find velodyne_description)/urdf/HDL-32E.urdf.xacro"/>
|
||||
<HDL-32E parent="base_link" name="velodyne2" topic="/velodyne_points2" hz="10" samples="220" gpu="${gpu}">
|
||||
<origin xyz="0 0 0.6" rpy="0 0 0" />
|
||||
</HDL-32E>
|
||||
|
||||
<xacro:include filename="$(find velodyne_description)/urdf/VLP-32C.urdf.xacro"/>
|
||||
<VLP-32C parent="base_link" name="velodyne3" topic="/velodyne_points3" hz="10" samples="1200" gpu="${gpu}">
|
||||
<origin xyz="0 0 0.8" rpy="0 0 0" />
|
||||
</VLP-32C>
|
||||
|
||||
</robot>
|
@ -0,0 +1,66 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.5">
|
||||
<world name="default">
|
||||
<!-- A global light source -->
|
||||
<include>
|
||||
<uri>model://sun</uri>
|
||||
</include>
|
||||
<!-- A ground plane -->
|
||||
<include>
|
||||
<uri>model://ground_plane</uri>
|
||||
</include>
|
||||
<!-- A unit box -->
|
||||
<model name='unit_box_0_0'>
|
||||
<pose frame=''>-1.5 2.5 0.5 0 -0 0</pose>
|
||||
<link name='link'>
|
||||
<inertial>
|
||||
<mass>1</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Grey</name>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
<kinematic>0</kinematic>
|
||||
<gravity>1</gravity>
|
||||
</link>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
@ -0,0 +1,397 @@
|
||||
<?xml version="1.0"?>
|
||||
<sdf version="1.6">
|
||||
<world name="default">
|
||||
|
||||
<light name='sun' type='directional'>
|
||||
<cast_shadows>1</cast_shadows>
|
||||
<pose>0 0 10 0 -0 0</pose>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<constant>0.9</constant>
|
||||
<linear>0.01</linear>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
</light>
|
||||
<include>
|
||||
<uri>model://ground_plane</uri>
|
||||
</include>
|
||||
<physics type='ode'>
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>1</real_time_factor>
|
||||
<real_time_update_rate>1000</real_time_update_rate>
|
||||
</physics>
|
||||
|
||||
<model name="base">
|
||||
<static>true</static>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>34 34 0.5</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>34 34 0.5</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1.2</mu>
|
||||
<mu2>1.2</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<model name="box0">
|
||||
<static>true</static>
|
||||
<pose>-2.55 -2 1.75 0 0 0</pose>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1.2</mu>
|
||||
<mu2>1.2</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<model name="box1">
|
||||
<static>true</static>
|
||||
<pose>10 15 1.75 0 0 0</pose>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1.2</mu>
|
||||
<mu2>1.2</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<model name="cylinder0">
|
||||
<static>true</static>
|
||||
<pose>2.8 -1.75 1.25 0 0 0</pose>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.5</radius>
|
||||
<length>2</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.5</radius>
|
||||
<length>2</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1.2</mu>
|
||||
<mu2>1.2</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<model name="cylinder1">
|
||||
<static>true</static>
|
||||
<pose>0.6 3.6 1.25 0 0 0</pose>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.5</radius>
|
||||
<length>2</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.5</radius>
|
||||
<length>2</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1.2</mu>
|
||||
<mu2>1.2</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<model name='jersey_barrier'>
|
||||
<static>1</static>
|
||||
<link name='link'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name='upright'>
|
||||
<pose>0 0 0.8215 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>4.06542 0.3063 1.143</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base'>
|
||||
<pose>0 0 0.032258 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>4.06542 0.8107 0.064516</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base2'>
|
||||
<pose>0 0 0.1 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>4.06542 0.65 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='base3'>
|
||||
<pose>0 0 0.2 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>4.06542 0.5 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='left-angle'>
|
||||
<pose>0 -0.224 0.2401 0.9 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>4.06542 0.5 0.064516</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='right-angle'>
|
||||
<pose>0 0.224 0.2401 -0.9 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>4.06542 0.5 0.064516</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<self_collide>0</self_collide>
|
||||
<enable_wind>0</enable_wind>
|
||||
<kinematic>0</kinematic>
|
||||
</link>
|
||||
<pose>0.591026 -4.27442 0 0 -0 0</pose>
|
||||
</model>
|
||||
|
||||
<model name='person_standing'>
|
||||
<link name='link'>
|
||||
<inertial>
|
||||
<pose>0 -0.1 1.2 0 -0 0</pose>
|
||||
<mass>80</mass>
|
||||
<inertia>
|
||||
<ixx>24.88</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>25.73</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>2.48</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='bottom'>
|
||||
<pose>0 -0.1 0.01 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.5 0.35 0.02</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<collision name='person'>
|
||||
<pose>0 0 0.02 0.04 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://person_standing/meshes/standing.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<pose>0 0 0.02 0.04 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://person_standing/meshes/standing.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<self_collide>0</self_collide>
|
||||
<enable_wind>0</enable_wind>
|
||||
<kinematic>0</kinematic>
|
||||
</link>
|
||||
<pose>6.65415 3.05596 0 0 -0 0</pose>
|
||||
</model>
|
||||
|
||||
<include>
|
||||
<uri>model://rs_robot</uri>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<static>false</static>
|
||||
</include>
|
||||
|
||||
</world>
|
||||
</sdf>
|
22
DRL_robot_navigation_ros2/src/td3/package.xml
Normal file
22
DRL_robot_navigation_ros2/src/td3/package.xml
Normal file
@ -0,0 +1,22 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>td3</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="robotmania@todo.todo">robotmania</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<depend>gazebo_ros_pkgs</depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
<gazebo_ros gazebo_model_path="${prefix}/models"/>
|
||||
</export>
|
||||
|
||||
</package>
|
209
DRL_robot_navigation_ros2/src/td3/scripts/point_cloud2.py
Normal file
209
DRL_robot_navigation_ros2/src/td3/scripts/point_cloud2.py
Normal file
@ -0,0 +1,209 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
"""
|
||||
Serialization of sensor_msgs.PointCloud2 messages.
|
||||
|
||||
Author: Tim Field
|
||||
ROS2 port by Sebastian Grans (2020)
|
||||
"""
|
||||
|
||||
import sys
|
||||
|
||||
from collections import namedtuple
|
||||
import ctypes
|
||||
import math
|
||||
import struct
|
||||
|
||||
from sensor_msgs.msg import PointCloud2, PointField
|
||||
|
||||
_DATATYPES = {}
|
||||
_DATATYPES[PointField.INT8] = ('b', 1)
|
||||
_DATATYPES[PointField.UINT8] = ('B', 1)
|
||||
_DATATYPES[PointField.INT16] = ('h', 2)
|
||||
_DATATYPES[PointField.UINT16] = ('H', 2)
|
||||
_DATATYPES[PointField.INT32] = ('i', 4)
|
||||
_DATATYPES[PointField.UINT32] = ('I', 4)
|
||||
_DATATYPES[PointField.FLOAT32] = ('f', 4)
|
||||
_DATATYPES[PointField.FLOAT64] = ('d', 8)
|
||||
|
||||
def read_points(cloud, field_names=None, skip_nans=False, uvs=[]):
|
||||
"""
|
||||
Read points from a L{sensor_msgs.PointCloud2} message.
|
||||
|
||||
@param cloud: The point cloud to read from.
|
||||
@type cloud: L{sensor_msgs.PointCloud2}
|
||||
@param field_names: The names of fields to read. If None, read all fields. [default: None]
|
||||
@type field_names: iterable
|
||||
@param skip_nans: If True, then don't return any point with a NaN value.
|
||||
@type skip_nans: bool [default: False]
|
||||
@param uvs: If specified, then only return the points at the given coordinates. [default: empty list]
|
||||
@type uvs: iterable
|
||||
@return: Generator which yields a list of values for each point.
|
||||
@rtype: generator
|
||||
"""
|
||||
assert isinstance(cloud, PointCloud2), 'cloud is not a sensor_msgs.msg.PointCloud2'
|
||||
fmt = _get_struct_fmt(cloud.is_bigendian, cloud.fields, field_names)
|
||||
width, height, point_step, row_step, data, isnan = cloud.width, cloud.height, \
|
||||
cloud.point_step, cloud.row_step, \
|
||||
cloud.data, math.isnan
|
||||
unpack_from = struct.Struct(fmt).unpack_from
|
||||
|
||||
if skip_nans:
|
||||
if uvs:
|
||||
for u, v in uvs:
|
||||
p = unpack_from(data, (row_step * v) + (point_step * u))
|
||||
has_nan = False
|
||||
for pv in p:
|
||||
if isnan(pv):
|
||||
has_nan = True
|
||||
break
|
||||
if not has_nan:
|
||||
yield p
|
||||
else:
|
||||
for v in range(height):
|
||||
offset = row_step * v
|
||||
for u in range(width):
|
||||
p = unpack_from(data, offset)
|
||||
has_nan = False
|
||||
for pv in p:
|
||||
if isnan(pv):
|
||||
has_nan = True
|
||||
break
|
||||
if not has_nan:
|
||||
yield p
|
||||
offset += point_step
|
||||
else:
|
||||
if uvs:
|
||||
for u, v in uvs:
|
||||
yield unpack_from(data, (row_step * v) + (point_step * u))
|
||||
else:
|
||||
for v in range(height):
|
||||
offset = row_step * v
|
||||
for u in range(width):
|
||||
yield unpack_from(data, offset)
|
||||
offset += point_step
|
||||
|
||||
def read_points_list(cloud, field_names=None, skip_nans=False, uvs=[]):
|
||||
"""
|
||||
Read points from a L{sensor_msgs.PointCloud2} message.
|
||||
|
||||
This function returns a list of namedtuples. It operates on top of the read_points method. For more efficient access use read_points directly.
|
||||
|
||||
@param cloud: The point cloud to read from.
|
||||
@type cloud: L{sensor_msgs.PointCloud2}
|
||||
@param field_names: The names of fields to read. If None, read all fields. [default: None]
|
||||
@type field_names: iterable
|
||||
@param skip_nans: If True, then don't return any point with a NaN value.
|
||||
@type skip_nans: bool [default: False]
|
||||
@param uvs: If specified, then only return the points at the given coordinates. [default: empty list]
|
||||
@type uvs: iterable
|
||||
@return: List of namedtuples containing the values for each point
|
||||
@rtype: list
|
||||
"""
|
||||
assert isinstance(cloud, PointCloud2), 'cloud is not a sensor_msgs.msg.PointCloud2'
|
||||
|
||||
if field_names is None:
|
||||
field_names = [f.name for f in cloud.fields]
|
||||
|
||||
Point = namedtuple("Point", field_names)
|
||||
|
||||
return [Point._make(l) for l in read_points(cloud, field_names, skip_nans, uvs)]
|
||||
|
||||
def create_cloud(header, fields, points):
|
||||
"""
|
||||
Create a L{sensor_msgs.msg.PointCloud2} message.
|
||||
|
||||
@param header: The point cloud header.
|
||||
@type header: L{std_msgs.msg.Header}
|
||||
@param fields: The point cloud fields.
|
||||
@type fields: iterable of L{sensor_msgs.msg.PointField}
|
||||
@param points: The point cloud points.
|
||||
@type points: list of iterables, i.e. one iterable for each point, with the
|
||||
elements of each iterable being the values of the fields for
|
||||
that point (in the same order as the fields parameter)
|
||||
@return: The point cloud.
|
||||
@rtype: L{sensor_msgs.msg.PointCloud2}
|
||||
"""
|
||||
cloud_struct = struct.Struct(_get_struct_fmt(False, fields))
|
||||
|
||||
buff = ctypes.create_string_buffer(cloud_struct.size * len(points))
|
||||
|
||||
point_step, pack_into = cloud_struct.size, cloud_struct.pack_into
|
||||
offset = 0
|
||||
for p in points:
|
||||
pack_into(buff, offset, *p)
|
||||
offset += point_step
|
||||
|
||||
return PointCloud2(header=header,
|
||||
height=1,
|
||||
width=len(points),
|
||||
is_dense=False,
|
||||
is_bigendian=False,
|
||||
fields=fields,
|
||||
point_step=cloud_struct.size,
|
||||
row_step=cloud_struct.size * len(points),
|
||||
data=buff.raw)
|
||||
|
||||
def create_cloud_xyz32(header, points):
|
||||
"""
|
||||
Create a L{sensor_msgs.msg.PointCloud2} message with 3 float32 fields (x, y, z).
|
||||
|
||||
@param header: The point cloud header.
|
||||
@type header: L{std_msgs.msg.Header}
|
||||
@param points: The point cloud points.
|
||||
@type points: iterable
|
||||
@return: The point cloud.
|
||||
@rtype: L{sensor_msgs.msg.PointCloud2}
|
||||
"""
|
||||
fields = [PointField('x', 0, PointField.FLOAT32, 1),
|
||||
PointField('y', 4, PointField.FLOAT32, 1),
|
||||
PointField('z', 8, PointField.FLOAT32, 1)]
|
||||
return create_cloud(header, fields, points)
|
||||
|
||||
def _get_struct_fmt(is_bigendian, fields, field_names=None):
|
||||
fmt = '>' if is_bigendian else '<'
|
||||
offset = 0
|
||||
for field in (f for f in sorted(fields, key=lambda f: f.offset) if field_names is None or f.name in field_names):
|
||||
if offset < field.offset:
|
||||
fmt += 'x' * (field.offset - offset)
|
||||
offset = field.offset
|
||||
if field.datatype not in _DATATYPES:
|
||||
print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr)
|
||||
else:
|
||||
datatype_fmt, datatype_length = _DATATYPES[field.datatype]
|
||||
fmt += field.count * datatype_fmt
|
||||
offset += field.count * datatype_length
|
||||
|
||||
return fmt
|
Binary file not shown.
Binary file not shown.
51
DRL_robot_navigation_ros2/src/td3/scripts/replay_buffer.py
Normal file
51
DRL_robot_navigation_ros2/src/td3/scripts/replay_buffer.py
Normal file
@ -0,0 +1,51 @@
|
||||
"""
|
||||
Data structure for implementing experience replay
|
||||
Author: Patrick Emami
|
||||
"""
|
||||
import random
|
||||
from collections import deque
|
||||
|
||||
import numpy as np
|
||||
|
||||
|
||||
class ReplayBuffer(object):
|
||||
def __init__(self, buffer_size, random_seed=123):
|
||||
"""
|
||||
The right side of the deque contains the most recent experiences
|
||||
"""
|
||||
self.buffer_size = buffer_size
|
||||
self.count = 0
|
||||
self.buffer = deque()
|
||||
random.seed(random_seed)
|
||||
|
||||
def add(self, s, a, r, t, s2):
|
||||
experience = (s, a, r, t, s2)
|
||||
if self.count < self.buffer_size:
|
||||
self.buffer.append(experience)
|
||||
self.count += 1
|
||||
else:
|
||||
self.buffer.popleft()
|
||||
self.buffer.append(experience)
|
||||
|
||||
def size(self):
|
||||
return self.count
|
||||
|
||||
def sample_batch(self, batch_size):
|
||||
batch = []
|
||||
|
||||
if self.count < batch_size:
|
||||
batch = random.sample(self.buffer, self.count)
|
||||
else:
|
||||
batch = random.sample(self.buffer, batch_size)
|
||||
|
||||
s_batch = np.array([_[0] for _ in batch])
|
||||
a_batch = np.array([_[1] for _ in batch])
|
||||
r_batch = np.array([_[2] for _ in batch]).reshape(-1, 1)
|
||||
t_batch = np.array([_[3] for _ in batch]).reshape(-1, 1)
|
||||
s2_batch = np.array([_[4] for _ in batch])
|
||||
|
||||
return s_batch, a_batch, r_batch, t_batch, s2_batch
|
||||
|
||||
def clear(self):
|
||||
self.buffer.clear()
|
||||
self.count = 0
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user