-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge branch 'main' into 43-well-gazebo-again
- Loading branch information
Showing
17 changed files
with
548 additions
and
59 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Large diffs are not rendered by default.
Oops, something went wrong.
Binary file not shown.
Large diffs are not rendered by default.
Oops, something went wrong.
Binary file not shown.
Large diffs are not rendered by default.
Oops, something went wrong.
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,98 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
<xacro:macro name="velodyne_lidar" params="name parent_link *origin | ||
ang_res_h:=0.4 min_ang_h:=-3.141592 max_ang_h:=3.141592 | ||
ang_res_v:=2.0 min_ang_v:=-0.261799 max_ang_v:=0.261799 | ||
update_rate:=20 min_range:=0.9 max_range:=130.0"> | ||
<link name="${name}_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="file://$(find rove_description)/meshes/vlp16/VLP16_base_1.dae"/> | ||
</geometry> | ||
</visual> | ||
<visual> | ||
<geometry> | ||
<mesh filename="file://$(find rove_description)/meshes/vlp16/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}_joint" type="fixed"> | ||
<xacro:insert_block name="origin"/> | ||
<parent link="${parent_link}"/> | ||
<child link="${name}_link"/> | ||
</joint> | ||
|
||
<link name="${name}_laser"> | ||
<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="file://$(find rove_description)/meshes/vlp16/VLP16_scan.dae"/> | ||
</geometry> | ||
</visual> | ||
</link> | ||
|
||
<joint name="${name}_laser_joint" type="fixed"> | ||
<origin xyz="0 0 0.0377" rpy="0 0 0"/> | ||
<parent link="${name}_link"/> | ||
<child link="${name}_laser"/> | ||
</joint> | ||
|
||
<xacro:property name="samples_h" value="${round((max_ang_h - min_ang_h) * 180 / (ang_res_h * pi))}"/> | ||
<xacro:property name="samples_v" value="${round((max_ang_v - min_ang_v) * 180 / (ang_res_v * pi))}"/> | ||
|
||
<gazebo reference="${name}_laser"> | ||
<sensor name="${name}" type="gpu_lidar"> | ||
<update_rate>${update_rate}</update_rate> | ||
<visualize>true</visualize> | ||
<always_on>true</always_on> | ||
<update_rate>5</update_rate> | ||
<topic>scan</topic> | ||
<gz_frame_id>${name}_laser</gz_frame_id> | ||
<lidar> | ||
<scan> | ||
<horizontal> | ||
<samples>${samples_h}</samples> | ||
<resolution>1</resolution> | ||
<min_angle>${min_ang_h}</min_angle> | ||
<max_angle>${max_ang_h}</max_angle> | ||
</horizontal> | ||
<vertical> | ||
<samples>${samples_v}</samples> | ||
<resolution>1</resolution> | ||
<min_angle>${min_ang_v}</min_angle> | ||
<max_angle>${max_ang_v}</max_angle> | ||
</vertical> | ||
</scan> | ||
<range> | ||
<min>${min_range}</min> | ||
<max>${max_range}</max> | ||
<resolution>0.01</resolution> | ||
</range> | ||
</lidar> | ||
</sensor> | ||
</gazebo> | ||
|
||
</xacro:macro> | ||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,131 @@ | ||
from launch import LaunchDescription | ||
from launch.actions import DeclareLaunchArgument | ||
from launch.substitutions import LaunchConfiguration | ||
from launch_ros.actions import Node | ||
|
||
def generate_launch_description(): | ||
|
||
lidar_frame_id = LaunchConfiguration('lidar_frame_id') | ||
|
||
use_sim_time = LaunchConfiguration('use_sim_time') | ||
deskewing = False | ||
|
||
return LaunchDescription([ | ||
|
||
|
||
DeclareLaunchArgument( | ||
'lidar_frame_id', default_value='velodyne_laser', | ||
description='Lidar frame id'), | ||
|
||
# Launch arguments | ||
DeclareLaunchArgument( | ||
'use_sim_time', default_value='true', | ||
description='Use simulation (Gazebo) clock if true'), | ||
|
||
DeclareLaunchArgument( | ||
'deskewing', default_value='true', | ||
description='Enable lidar deskewing'), | ||
|
||
# Nodes to launch | ||
Node( | ||
package='rtabmap_odom', executable='icp_odometry', output='screen', | ||
parameters=[{ | ||
'frame_id': lidar_frame_id, # 'livox_frame' | ||
'odom_frame_id': 'odom', | ||
'wait_for_transform': 0.2, | ||
'expected_update_rate': 50.0, | ||
'deskewing': deskewing, | ||
'use_sim_time': use_sim_time, | ||
}], | ||
remappings=[ | ||
('scan_cloud', '/velodyne_points') | ||
], | ||
arguments=[ | ||
'Icp/PointToPlane', 'true', | ||
'Icp/Iterations', '10', | ||
'Icp/VoxelSize', '0.1', | ||
'Icp/Epsilon', '0.001', | ||
'Icp/PointToPlaneK', '20', | ||
'Icp/PointToPlaneRadius', '0', | ||
'Icp/MaxTranslation', '2', | ||
'Icp/MaxCorrespondenceDistance', '1', | ||
'Icp/Strategy', '1', | ||
'Icp/OutlierRatio', '0.7', | ||
'Icp/CorrespondenceRatio', '0.01', | ||
'Odom/ScanKeyFrameThr', '0.4', | ||
'OdomF2M/ScanSubtractRadius', '0.1', | ||
'OdomF2M/ScanMaxSize', '15000', | ||
'OdomF2M/BundleAdjustment', 'false', | ||
]), | ||
|
||
Node( | ||
package='rtabmap_util', executable='point_cloud_assembler', output='screen', | ||
parameters=[{ | ||
'max_clouds': 10, | ||
'fixed_frame_id': '', | ||
'use_sim_time': use_sim_time, | ||
}], | ||
remappings=[ | ||
('cloud', '/velodyne_points') | ||
]), | ||
|
||
Node( | ||
package='rtabmap_slam', executable='rtabmap', output='screen', | ||
parameters=[{ | ||
'frame_id': lidar_frame_id, # 'livox_frame' | ||
'subscribe_depth': False, | ||
'subscribe_rgb': False, | ||
'subscribe_scan_cloud': True, | ||
'approx_sync': False, | ||
'wait_for_transform': 0.2, | ||
'use_sim_time': use_sim_time, | ||
'wait_imu_to_int': True, | ||
'imu_topic': 'imu', | ||
}], | ||
remappings=[ | ||
('scan_cloud', 'assembled_cloud') | ||
], | ||
arguments=[ | ||
'-d', # This will delete the previous database (~/.ros/rtabmap.db) | ||
'RGBD/ProximityMaxGraphDepth', '0', | ||
'RGBD/ProximityPathMaxNeighbors', '1', | ||
'RGBD/AngularUpdate', '0.05', | ||
'RGBD/LinearUpdate', '0.05', | ||
'RGBD/CreateOccupancyGrid', 'true', | ||
'Mem/NotLinkedNodesKept', 'false', | ||
'Mem/STMSize', '30', | ||
'Mem/LaserScanNormalK', '20', | ||
'Reg/Strategy', '1', | ||
'Icp/VoxelSize', '0.5', | ||
'Icp/PointToPlaneK', '20', | ||
'Icp/PointToPlaneRadius', '0', | ||
'Icp/PointToPlane', 'true', | ||
'Icp/Iterations', '10', | ||
'Icp/Epsilon', '0.001', | ||
'Icp/MaxTranslation', '3', | ||
'Icp/MaxCorrespondenceDistance', '1', | ||
'Icp/Strategy', '1', | ||
'Icp/OutlierRatio', '0.7', | ||
'Icp/CorrespondenceRatio', '0.2', | ||
'Grid/MaxGroundHeight', '0.05', | ||
'Grid/MaxObstacleHeight', '1.5', | ||
'Reg/Force3DoF', 'true', | ||
'Optimizer/Slam2D', 'true', | ||
|
||
]), | ||
|
||
Node( | ||
package='rtabmap_viz', executable='rtabmap_viz', output='screen', | ||
parameters=[{ | ||
'frame_id': lidar_frame_id, | ||
'odom_frame_id': 'odom', | ||
'subscribe_odom_info': True, | ||
'subscribe_scan_cloud': True, | ||
'approx_sync': False, | ||
'use_sim_time': use_sim_time, | ||
}], | ||
remappings=[ | ||
('scan_cloud', 'odom_filtered_input_scan') | ||
]), | ||
]) | ||
|
Oops, something went wrong.