Skip to content

Commit

Permalink
Add lidarbot_gz package to use Gazebo Fortress
Browse files Browse the repository at this point in the history
  • Loading branch information
TheNoobInventor committed Aug 22, 2024
1 parent b5f91cd commit 0178bc8
Show file tree
Hide file tree
Showing 26 changed files with 2,344 additions and 38 deletions.
38 changes: 21 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ Hardware components are written for the Waveshare Motor Driver HAT and MPU6050 s
- [`lidarbot_bringup`](./lidarbot_bringup/) : Contains hardware component for the MPU6050 module, launch files to bring up the camera, lidar and the real lidarbot.
- [`lidarbot_description`](./lidarbot_description/) : Contains the URDF description files for lidarbot, sensors and `ros2 control`.
- [`lidarbot_gazebo`](./lidarbot_gazebo/) : Contains configuration, launch and world files needed to simulate lidarbot in Gazebo Classic.
- [`lidarbot_gz`](./lidarbot_gz/) : Contains urdf, launch and world files needed to simulate lidarbot in Gazebo Fortress.
- [`lidarbot_navigation`](./lidarbot_navigation/) : Contains launch, configuration and map files used for lidarbot navigation.
- [`lidarbot_slam`](./lidarbot_slam/) : Contains configuration files for the slam toolbox and RViz, launch file to generate maps using SLAM.
- [`lidarbot_teleop`](./lidarbot_teleop/) : Contains configuration and launch files used to enable joystick control of the lidarbot in simulation and physically.
Expand All @@ -72,21 +73,21 @@ The following components were used in this project:
|2| SanDisk 32 GB SD Card (minimum)|
|3| [Two wheel drive robot chassis kit](https://www.amazon.com/perseids-Chassis-Encoder-Wheels-Battery/dp/B07DNYQ3PX/ref=sr_1_9?crid=3T8FVRRMPFCIX&keywords=two+wheeled+drive+robot+chassis&qid=1674141374&sprefix=two+wheeled+drive+robot+chas%2Caps%2C397&sr=8-9)|
|4| [Waveshare Motor Driver HAT](https://www.waveshare.com/wiki/Motor_Driver_HAT)|
|5| 2 x [Motors with encoders](https://www.aliexpress.com/item/1005006363532248.html?spm=a2g0o.detail.pcDetailTopMoreOtherSeller.6.5fdeSplESplEAo&gps-id=pcDetailTopMoreOtherSeller&scm=1007.40050.354490.0&scm_id=1007.40050.354490.0&scm-url=1007.40050.354490.0&pvid=1fbd5a28-56b9-49ff-ad51-948875853e0c&_t=gps-id:pcDetailTopMoreOtherSeller,scm-url:1007.40050.354490.0,pvid:1fbd5a28-56b9-49ff-ad51-948875853e0c,tpp_buckets:668%232846%238109%231935&utparam-url=scene%3ApcDetailTopMoreOtherSeller%7Cquery_from%3A)|
|6| 2 x [PH 2.0 Motor pin connectors](https://s.click.aliexpress.com/e/_Dl669tn)
|7| MPU6050 board|
|8| [RPlidar A1](https://s.click.aliexpress.com/e/_DdPdRS7)|
|9| Raspberry Pi camera v1.3|
|10| [3D printed stands for RPlidar A1 and RPi 4](https://www.thingiverse.com/thing:3970110)|
|11| Mount for Raspberry Pi camera|
|12| Powerbank for RPi 4 (minimum output: 5V 3A)|
|13| Gamepad|
|14| [Mini Travel Router](https://s.click.aliexpress.com/e/_DcgfT61)|
|15| 3 Slot 18650 battery holder|
|16| 3 x 18650 batteries to power Motor Driver HAT|
|17| Female to Female Dupont jumper cables|
|18| Spare wires|
|19| Logitech C270 webcam|
|5| 2 x [Motors with encoders and wire harness](https://s.click.aliexpress.com/e/_DBL19Mr|
<!-- |6| 2 x [PH 2.0 Motor pin connectors](https://s.click.aliexpress.com/e/_Dl669tn) -->
|6| MPU6050 board|
|7| [RPlidar A1](https://s.click.aliexpress.com/e/_DdPdRS7)|
|8| Raspberry Pi camera v1.3|
|9| [3D printed stands for RPlidar A1 and RPi 4](https://www.thingiverse.com/thing:3970110)|
|10| Mount for Raspberry Pi camera|
|11| Powerbank for RPi 4 (minimum output: 5V 3A)|
|12| Gamepad|
|13| [Mini Travel Router](https://s.click.aliexpress.com/e/_DcgfT61)|
|14| 3 Slot 18650 battery holder|
|15| 3 x 18650 batteries to power Motor Driver HAT|
|16| Female to Female Dupont jumper cables|
|17| Spare wires|
|18| Logitech C270 webcam|

Some other tools or parts used in the project are as follows:

Expand Down Expand Up @@ -118,7 +119,7 @@ The MPU6050 board pins were connected to the Raspberry Pi 4 GPIO pins as follows

In a previous hardware version of lidarbot, photo interrupters were used with encoder disks with 20 slots (included in the robot chassis kit). However, this setup proved restrictive in yielding satisfactory results in navigation due to the low number of encoder ticks, 20. Therefore, the robot chassis kit motors were replaced with the ones below with built-in encoders --- which have encoder ticks of approximately 1084, calculated using this [guide](https://automaticaddison.com/calculate-pulses-per-revolution-for-a-dc-motor-with-encoder/) from Automatic Addison.

These are new motors used for lidarbot:
These are the new motors used for lidarbot:

<p align="center">
<img title='Motors' src=docs/images/motors.jpg width="400">
Expand Down Expand Up @@ -291,7 +292,10 @@ colcon build --symlink-install
The `--symlink-install` argument uses symlinks instead of copies which saves you from having to rebuild every time you [tweak certain files](https://articulatedrobotics.xyz/ready-for-ros-5-packages/).


#### Gazebo
#### Gazebo Classic

TODO: Add update on using Gazebo Fortress

Gazebo classic, version 11, is the robot simulator used in the project and can be installed [here](https://classic.gazebosim.org/tutorials?tut=install_ubuntu&cat=install).

#### Display lidarbot model in RViz
Expand Down
7 changes: 2 additions & 5 deletions lidarbot_bringup/launch/lidarbot_bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,6 @@ def generate_launch_description():

# Spawn joint_state_broadcaser
start_joint_broadcaster_cmd = Node(
# condition=IfCondition(use_ros2_control),
package="controller_manager",
executable="spawner",
arguments=["joint_broadcaster", "--controller-manager", "/controller_manager"],
Expand All @@ -114,12 +113,11 @@ def generate_launch_description():
)
)

# Spawn imu_sensor_broadcaser
# Spawn imu_sensor_broadcaster
start_imu_broadcaster_cmd = Node(
# condition=IfCondition(use_ros2_control),
package="controller_manager",
executable="spawner",
arguments=["imu_broadcaster"],
arguments=["imu_broadcaster", "--controller-manager", "/controller_manager"],
)

# Delayed imu_broadcaster_spawner action
Expand Down Expand Up @@ -190,4 +188,3 @@ def generate_launch_description():
return ld

# TODO: Launch file summary

56 changes: 41 additions & 15 deletions lidarbot_description/launch/robot_state_publisher_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,38 +12,64 @@
def generate_launch_description():

# Launch config variables
use_sim_time = LaunchConfiguration('use_sim_time')
use_ros2_control = LaunchConfiguration('use_ros2_control')
use_sim_time = LaunchConfiguration("use_sim_time")
use_ros2_control = LaunchConfiguration("use_ros2_control")
urdf_path = LaunchConfiguration("urdf_path")

# Process files
pkg_path = FindPackageShare(package='lidarbot_description').find('lidarbot_description')
urdf_model_path = os.path.join(pkg_path, 'urdf/lidarbot.urdf.xacro')
robot_description_config = Command(['xacro ', urdf_model_path, ' use_ros2_control:=', use_ros2_control, ' sim_mode:=', use_sim_time])
pkg_path = FindPackageShare(package="lidarbot_description").find(
"lidarbot_description"
)
urdf_model_path = os.path.join(pkg_path, "urdf/lidarbot.urdf.xacro")

# Declare the launch arguments
declare_use_sim_time_cmd = DeclareLaunchArgument(
name='use_sim_time',
default_value='False',
description='Use simulation (Gazebo) time if true')
name="use_sim_time",
default_value="False",
description="Use simulation (Gazebo) time if true",
)

declare_use_ros2_control_cmd = DeclareLaunchArgument(
name='use_ros2_control',
default_value='False',
description='Use ros2_control if true')
name="use_ros2_control",
default_value="False",
description="Use ros2_control if true",
)

declare_urdf_path = DeclareLaunchArgument(
name="urdf_path",
default_value=urdf_model_path,
description="Path to the main urdf model",
)

robot_description_config = Command(
[
"xacro ",
urdf_path,
" use_ros2_control:=",
use_ros2_control,
" sim_mode:=",
use_sim_time,
]
)

# Start robot state publisher node
params = {'robot_description': robot_description_config, 'use_sim_time': use_sim_time}
params = {
"robot_description": robot_description_config,
"use_sim_time": use_sim_time,
}
start_robot_state_publisher_cmd = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[params])
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[params],
)

# Create the launch description and populate
ld = LaunchDescription()

# Declare the launch options
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_use_ros2_control_cmd)
ld.add_action(declare_urdf_path)

# Add any actions
ld.add_action(start_robot_state_publisher_cmd)
Expand Down
5 changes: 5 additions & 0 deletions lidarbot_description/urdf/ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,11 @@
</ros2_control>
</xacro:if>

<!-- ADD FLAG FOR FORTRESS -->
<!-- WHAT ABOUT THE LIDAR SENSOR FOR FORTRESS? -->
<!-- DO WE HAVE TO CREATE A NEW BRANCH INSTEAD -->
<!-- OR MAYBE HAVE OUR OWN URDF DIRECTORY LIKE ANDINO DID -->

<gazebo>
<plugin name='gazebo_ros2_control' filename='libgazebo_ros2_control.so'>
<parameters>$(find lidarbot_bringup)/config/controllers.yaml</parameters>
Expand Down
2 changes: 1 addition & 1 deletion lidarbot_gazebo/launch/gazebo_launch.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# Launches the lidarbot in Gazebo to be controlled using a joystick. There are a number of launch arguments that can be toggled.
# Such as using the gazebo_ros plugin or the ros2_control plugin, using Gazebo's sim time or not.
# Such as using the gazebo_ros package or the ros2_control package, using Gazebo's sim time or not.
#
# File adapted from https://automaticaddison.com

Expand Down
13 changes: 13 additions & 0 deletions lidarbot_gz/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
cmake_minimum_required(VERSION 3.8)
project(lidarbot_gz)

find_package(ament_cmake REQUIRED)
find_package(urdf REQUIRED)

install(
DIRECTORY config launch models urdf worlds
DESTINATION share/${PROJECT_NAME}
)

ament_package()

57 changes: 57 additions & 0 deletions lidarbot_gz/config/lidarbot_bridge.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
# gz topic published by the simulator core
- ros_topic_name: "clock"
gz_topic_name: "clock"
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "gz.msgs.Clock"
direction: GZ_TO_ROS

# gz topic published by JointState plugin
# - ros_topic_name: "joint_states"
# gz_topic_name: "joint_states"
# ros_type_name: "sensor_msgs/msg/JointState"
# gz_type_name: "gz.msgs.Model"
# direction: GZ_TO_ROS

# gz topic published by DiffDrive plugin
# - ros_topic_name: "odom"
# gz_topic_name: "odom"
# ros_type_name: "nav_msgs/msg/Odometry"
# gz_type_name: "gz.msgs.Odometry"
# direction: GZ_TO_ROS

# gz topic published by DiffDrive plugin
# - ros_topic_name: "tf"
# gz_topic_name: "tf"
# ros_type_name: "tf2_msgs/msg/TFMessage"
# gz_type_name: "gz.msgs.Pose_V"
# direction: GZ_TO_ROS

# gz topic subscribed to by DiffDrive plugin
# - ros_topic_name: "cmd_vel"
# gz_topic_name: "cmd_vel"
# ros_type_name: "geometry_msgs/msg/Twist"
# gz_type_name: "gz.msgs.Twist"
# direction: ROS_TO_GZ

# gz topic published by IMU plugin
# - ros_topic_name: "imu"
# gz_topic_name: "imu"
- ros_topic_name: "imu_broadcaster/imu"
gz_topic_name: "imu_broadcaster/imu"
ros_type_name: "sensor_msgs/msg/Imu"
gz_type_name: "gz.msgs.IMU"
direction: GZ_TO_ROS

# gz topic published by Sensors plugin
- ros_topic_name: "scan"
gz_topic_name: "scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS

# gz topic published by Sensors plugin (Camera)
- ros_topic_name: "camera/camera_info"
gz_topic_name: "camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
direction: GZ_TO_ROS
Loading

0 comments on commit 0178bc8

Please sign in to comment.