Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 19 additions & 14 deletions config/ydlidar.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,10 @@ Panels:
Expanded:
- /Global Options1
- /Status1
- /LaserScan1
- /LaserScan1/Topic1
Splitter Ratio: 0.5
Tree Height: 617
Tree Height: 787
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expand Down Expand Up @@ -53,25 +54,26 @@ Visualization Manager:
Channel Name: intensity
Class: rviz_default_plugins/LaserScan
Color: 239; 41; 41
Color Transformer: FlatColor
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 1012
Max Intensity: 1016
Min Color: 0; 0; 0
Min Intensity: 1008
Name: LaserScan
Position Transformer: XYZ
Selectable: true
Size (Pixels): 3
Size (m): 0.05999999865889549
Style: Flat Squares
Style: Spheres
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: System Default
Reliability Policy: Best Effort
Value: /scan
Use Fixed Frame: true
Use rainbow: true
Expand Down Expand Up @@ -111,6 +113,9 @@ Visualization Manager:
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
Expand Down Expand Up @@ -139,7 +144,7 @@ Visualization Manager:
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 10
Distance: 12
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Expand All @@ -149,29 +154,29 @@ Visualization Manager:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 1.5103975534439087
Pitch: 1.5697963237762451
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 6.163581848144531
Yaw: 3.1414999961853027
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Height: 1016
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002f4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002f4000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002f4000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000023f000002f400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd0000000400000000000001560000039efc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000039e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000039efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000039e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004c90000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 67
Y: 60
Width: 1850
X: 70
Y: 27
10 changes: 7 additions & 3 deletions launch/ydlidar_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,13 @@ def generate_launch_description():
node_namespace='/',
)
tf2_node = Node(package='tf2_ros',
node_executable='static_transform_publisher',
node_name='static_tf_pub_laser',
arguments=['0', '0', '0.02','0', '0', '0', '1','base_link','laser_frame'],
node_executable='static_transform_publisher',
node_name='static_tf_pub_laser',
arguments=[
"--x", "0", "--y", "0", "--z", "0.02",
"--qx", "0", "--qy", "0", "--qz", "0", "--qw", "1",
"--frame-id", "base_link", "--child-frame-id", "laser_frame"
]
)

return LaunchDescription([
Expand Down
22 changes: 13 additions & 9 deletions launch/ydlidar_launch_view.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,22 +37,26 @@ def generate_launch_description():
description='FPath to the ROS2 parameters file to use.')

driver_node = LifecycleNode(package='ydlidar_ros2_driver',
node_executable='ydlidar_ros2_driver_node',
node_name='ydlidar_ros2_driver_node',
executable='ydlidar_ros2_driver_node',
name='ydlidar_ros2_driver_node',
output='screen',
emulate_tty=True,
parameters=[parameter_file],
node_namespace='/',
namespace='',
)
tf2_node = Node(package='tf2_ros',
node_executable='static_transform_publisher',
node_name='static_tf_pub_laser',
arguments=['0', '0', '0.02','0', '0', '0', '1','base_link','laser_frame'],
executable='static_transform_publisher',
name='static_tf_pub_laser',
arguments=[
"--x", "0", "--y", "0", "--z", "0.02",
"--qx", "0", "--qy", "0", "--qz", "0", "--qw", "1",
"--frame-id", "base_link", "--child-frame-id", "laser_frame"
]
)
rviz2_node = Node(package='rviz2',
node_executable='rviz2',
node_name='rviz2',
arguments=['-d', rviz_config_file],
executable='rviz2',
name='rviz2',
arguments=['-d', rviz_config_file],
)

return LaunchDescription([
Expand Down