Skip to content

Commit

Permalink
Merge branch 'main' into 43-well-gazebo-again
Browse files Browse the repository at this point in the history
  • Loading branch information
SimonR99 authored Apr 6, 2024
2 parents 70a31a2 + ea74103 commit 94fa288
Show file tree
Hide file tree
Showing 17 changed files with 548 additions and 59 deletions.
9 changes: 7 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -54,13 +54,18 @@ IF YOU ARE RUNNING IN WSL: do this command
```bash
export LIBGL_ALWAYS_INDIRECT=0 export LIBGL_ALWAYS_SOFTWARE=1
```
Do these commands to run the simulation
Do these commands to run the gazebo simulation with physics enabled
```bash
colcon build --symlink-install
source install/setup.bash
ros2 launch rove_description sim.launch.py
```

OR Do these commands to only run the rviz simulation (with joints control)
```bash
colcon build --symlink-install
source install/setup.bash
ros2 launch rove_description launch.py
```

## Running the controller with a usb cable

Expand Down
5 changes: 5 additions & 0 deletions rove.repos
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,8 @@ repositories:
type: git
url: https://github.com/clubcapra/capra_gazebo.git
version: main
ovis_description:
type: git
url: https://github.com/clubcapra/ovis_ros2.git
version: master

7 changes: 7 additions & 0 deletions src/rove_description/config/default_bridge.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,13 @@
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS

# gz topic published by Sensors plugin (point cloud)
- ros_topic_name: "velodyne_points"
gz_topic_name: "/scan/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "gz.msgs.PointCloudPacked"
direction: GZ_TO_ROS

# gz topic published by JointState plugin
- ros_topic_name: "joint_states"
gz_topic_name: "joint_states"
Expand Down
11 changes: 11 additions & 0 deletions src/rove_description/launch/sim.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,16 @@ def generate_launch_description():
}.items(),
)

slam3d = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_rove_slam, "launch", "slam3d.launch.py"),
),
launch_arguments={
"use_sim_time": "true",
"deskewing": "true",
}.items(),
)

nav = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_rove_nav, "navigation.launch.py"),
Expand All @@ -117,6 +127,7 @@ def generate_launch_description():
robot_localization_node,
rviz,
slam,
#slam3d,
create,
nav,
])
89 changes: 89 additions & 0 deletions src/rove_description/meshes/vlp16/VLP16_base_1.dae

Large diffs are not rendered by default.

Binary file not shown.
89 changes: 89 additions & 0 deletions src/rove_description/meshes/vlp16/VLP16_base_2.dae

Large diffs are not rendered by default.

Binary file not shown.
89 changes: 89 additions & 0 deletions src/rove_description/meshes/vlp16/VLP16_scan.dae

Large diffs are not rendered by default.

Binary file added src/rove_description/meshes/vlp16/VLP16_scan.stl
Binary file not shown.
1 change: 1 addition & 0 deletions src/rove_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>velodyne_description</exec_depend>

<buildtool_depend>ament_cmake</buildtool_depend>

Expand Down
60 changes: 6 additions & 54 deletions src/rove_description/urdf/lidar.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,61 +2,13 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:property name="M_PI" value="3.1415926535897931" />

<xacro:include filename="$(find rove_description)/urdf/velodyne.urdf.xacro" />

<joint name="laser_joint" type="fixed">
<parent link="base_link"/>
<child link="base_scan"/>
<origin xyz="0.0 0 0.4" rpy="0 0 0"/>
</joint>
<xacro:velodyne_lidar name="velodyne" parent_link="base_link">

<link name="base_scan">
<visual>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.1" />
<inertia ixx="${(1/12) * 0.1 * (3*0.05*0.05 + 0.04*0.04)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * 0.1 * (3*0.05*0.05 + 0.04*0.04)}" iyz="0.0"
izz="${(1/2) * 0.1 * (0.05*0.05)}" />
</inertial>
</link>
<origin xyz="0.0 0.0 0.4" rpy="0 0 0" />

<gazebo reference="base_scan">
<material>Gazebo/Black</material>
</xacro:velodyne_lidar>

<sensor name='laser_sensor_frame' type='gpu_lidar'>
<pose> 0 0 0 0 0 0 </pose>
<visualize>true</visualize>
<always_on>true</always_on>
<update_rate>5</update_rate>
<topic>scan</topic>
<gz_frame_id>base_scan</gz_frame_id>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
</scan>
<range>
<min>1</min>
<max>50</max>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</ray>
</sensor>
</gazebo>
</robot>
</robot>
8 changes: 8 additions & 0 deletions src/rove_description/urdf/rove.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
<xacro:include filename="$(find rove_description)/urdf/flipper.urdf.xacro" />
<xacro:include filename="$(find rove_description)/urdf/track.urdf.xacro" />

<xacro:include filename="$(find ovis_description)/urdf/ovis.urdf.xacro" />

<link name="base_footprint"/>

<link name="base_link">
Expand Down Expand Up @@ -46,4 +48,10 @@
<child link="base_link"/>
</joint>

<!-- Insert ovis on top of rove -->
<xacro:property name="robot_root" value="base_link" />
<xacro:property name="ovis_robot_namespace" value="rove" />
<xacro:property name="ovis_base_origin" value="-0.2 0 0.2" />
<xacro:ovis base_parent="${robot_root}" prefix="${ovis_robot_namespace}" joint_base_origin_xyz="${ovis_base_origin}" />

</robot>
98 changes: 98 additions & 0 deletions src/rove_description/urdf/velodyne.urdf.xacro
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>
131 changes: 131 additions & 0 deletions src/rove_slam/launch/slam3d.launch.py
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')
]),
])

Loading

0 comments on commit 94fa288

Please sign in to comment.