rursprung / fhgr-mrproj2

A ROS 1 based tank with a LIDAR.
GNU General Public License v3.0
2 stars 1 forks source link
cpp gazebo lidar raspberrypi robot ros ros-noetic

Mobile Robotics Project 2

CI License: GPLv3

As part of the FHGR BSc Mobile Robotics an autonomous vehicle with Lidar has been developed as a group project by Tim Barmettler, Joel Flepp, Yan Gridling and Ralph Ursprung in the 4th semester.

This repository contains both the code as well as the PCB schematics and the 3D printing files which should allow anyone to build the same robot as an open-source project.

What Does "SMT" Mean?

"SMT" stands for "Super Mega Tank". The name was inspired by the Super Mega Bot (SMB) from ETHZ.

Features

The robot can be operated using the keyboard and driven around. While driving, it creates a map of its environment. In parallel, a camera is used to scan for a QR code and if this is found, the gun will shoot at the QR code.

GUI

rviz is used to visualise the map, the position of the robot within it as well as the camera feed (with QR codes being highlighted). Optionally the location of a QR code which has been found can be highlighted as well.

Mapping

A 2D map is being created using SLAM and can be downloaded using hector_geotiff. If it is not downloaded, the data will be lost once the software is stopped / the robot powered down. Currently, the robot does not support loading a pre-made map and continue mapping in it.

To save the map to smt_slam/maps run:

rostopic pub /syscommand std_msgs/String -1 "data: 'savegeiff'"

Architecture

Structure

The software is structured along these boundaries:

graph TD
  Teleop -->|"move command<br/>message: <code>geometry_msgs/Twist</code><br/>topic: <code>/cmd_vel</code>"| MC

MC[ Movement Controller ]
MC -->| PWM signal| LM[[ Left Motor ]]
MC -->|PWM signal | RM[[ Right Motor ]]

Camera[[ Camera ]] --> CameraController
CameraController[ Camera Controller ] -->|"image<br/>message: <code>sensor_msgs/Image</code><br/>topic: <code>/camera1/image_raw</code>"| QRCodeFinder
QRCodeFinder[ QR Code Finder ] -->|"QR Code Pose<br/>message: <code>smt_msgs/PoseWithString</code><br/>(= <code>geometry_msgs/Pose</code> + <code>string</code>)<br/>topic: <code>/qr_codes</code>"| QRCodeController

QRCodeController[ QR Code Controller ] -->|"fire command<br/>service: <code>FireAt</code><br/>request:<code>std_msgs/Int32</code> (angle)"| GC
GC[ Gun Controller ] -->| PWM signal| GS
GC -->| Trigger signal | GT
GS[["Gun Servo (height adjust)"]]
GT[[ Gun Trigger ]]

LIDAR[[LIDAR ]] --> rplidar
rplidar[ rplidar_ros ] -->|"point cloud<br/>message: <code>sensor_msgs/LaserScan</code><br/>topic: <code>/scan</code>"| hector_mapping

IMU[["IMU (Bosch BNO055)"]] --> IMUdriver
IMUdriver[ Bosch IMU Driver ] -->|"IMU data<br/>message: <code>sensor_msgs/Imu</code><br/>topic: <code>/imu</code>"| ekf_localization

ekf_localization -->| odom | hector_mapping
ekf_localization -->|odom | tf
hector_mapping["Hector Mapping (SLAM)"] -->| map | tf

hector_mapping -->|"Pose Estimate<br/>message: <code>geometry_msgs/PoseStamped</code><br/>topic: <code>/poseupdate</code>"| ekf_localization

model[ Robot Model ]
model --> robot_state_publisher
model --> joint_state_publisher
robot_state_publisher --> tf
joint_state_publisher --> tf

Note that various helper ROS nodes are not shown here. Only the main components are shown.

When running in a simulator (gazebo) the hardware related controllers will be replaced with simulator versions thereof, which will then interact with gazebo rather than the real hardware.

Convention used (& invented) for this diagram:

State

stateDiagram-v2
  [*] --> D: turn on
  D --> G: target identified
  G --> D: shot fired

  D: Drive mode (Mapping, QR Code Search)
  G: Gun Mode (shoot at target)

Working With This Repository

As this repository contains code for ROS (specifically, ROS noetic, the last 1.x release) and uses the catkin build tool, you'll need to work in a catkin workspace.

  1. Source your ROS setup script (you should preferably add this to your ~/.profile, esp. if you're working with an IDE!)
    source /opt/ros/noetic/setup.bash
  2. Create a new folder for your new catkin workspace (note: you can have multiple catkin workspaces in parallel and also source all of their setup.bash files at the same time, that works fine):
    cd <wherever you want to have your workspace>/src
  3. Clone this repository into the src folder of the workspace:
    git clone --recurse-submodules https://github.com/rursprung/fhgr-mrproj2.git

    Notes:

  1. Install all required dependencies:

    rosdep install --from-paths . -i
    
    sudo pip install pynput # see https://github.com/ethz-asl/better_teleop for more details
  2. Build the workspace & source its setup file:
    catkin build
    source devel/setup.bash
  3. Optional: when working with an IDE you should add the sourcing of the setup.bash of your workspace also to your ~/.profile (same as the one from ROS) so that it's set for all sessions and your IDE can access it!

Contributing To The Repository

If you intend to contribute to the repository, please make sure that you're using a fork rather than working directly in the upstream repository!

Follow the guide above to set up your repository and then:

  1. Create your fork on GitHub if you haven't done so already
  2. Go to your local clone of the repository:
    cd <your workspace>/src
  3. Rename the remote origin to upstream:
    git remote rename origin upstream
  4. Add your own fork:
    git remote add origin <your fork URL>
    git fetch --all
  5. Follow the contribution guide for further details.

Running The Code

Simulation

After building the project you can run the simulated robot using:

roslaunch smt_launch_gazebo default.launch

You can use the arrow keys to navigate in the world.

On the Robot

To run the code on the robot you initially need to set up the udev rules for the LIDAR:

$(rospack find rplidar_ros)/scripts/create_udev_rules.sh

This only needs to be done once.

Due to the limited computational power of the Raspberry Pi the compute heavy tasks have been offloaded to a more capable computer (usually a ROS-specific VM running on your notebook). Accordingly, there are two launch packages, one for the robot and one for the remote device (which will also start rviz and teleop). In order for the two to be able to communicate you need to ensure that they can see each other in the network. Note that for VMs this means that they must have a bridged network adapter instead of NAT so that they have an IP by which they're reachable from the outside. You'll also need to start roscore on one of the two and then set the ROS_MASTER_URI on the second to the first (check the roscore output there for the URL with the port number). Furthermore, it's likely that you need to set the ROS_IP and ROS_HOSTNAME for things to work properly.

Afterward you can launch the hardware part on the robot:

roslaunch smt_launch_hardware default.launch

And the remote control part on your computer:

roslaunch smt_launch_remote_control default.launch

License

As this is purely an educational project there's no need for others to include it in their commercial works. Accordingly, this is licensed under the GNU General Public License v3.0 or later (SPDX: GPL-3.0-or-later). See LICENSE for the full license text.