|
1 |
| -# Diffbot ROS Packages |
2 |
| - |
3 |
| -The following describes the easiest way to make use of diffbot's ROS packages inside the [ros-mobile-robots/diffbot](https://github.com/ros-mobile-robots/diffbot) |
4 |
| -repository. |
5 |
| - |
6 |
| -The following steps will be performed on both, the workstation/development PC and the single board computer (SBC). |
7 |
| - |
8 |
| -## Git: clone diffbot repository |
9 |
| - |
10 |
| -After setting up ROS on your workstation PC and the SBC (either [Raspberry Pi 4B](https://ros-mobile-robots.com/rpi-setup/) or [Jetson Nano](https://ros-mobile-robots.com/jetson-nano-setup/)), |
11 |
| -create a ros workspace in your users home folder and clone the [`diffbot` repository]({{ diffbot_repo_url }}): |
12 |
| - |
13 |
| -``` |
14 |
| -mkdir -p ros_ws/src |
15 |
| -git clone https://github.com/ros-mobile-robots/diffbot.git |
16 |
| -``` |
17 |
| - |
18 |
| -## Obtain (system) Dependencies |
19 |
| - |
20 |
| -The `diffbot` repository relies on two sorts of dependencies: |
21 |
| - |
22 |
| -- Source (non binary) dependencies from other (git) repositories. |
23 |
| -- System dependencies available in the (ROS) Ubuntu package repositories. Also refered to as pre built binaries. |
24 |
| - |
25 |
| - |
26 |
| -### Source Dependencies |
27 |
| - |
28 |
| -Let's first obtain source dependencies from other repositories. |
29 |
| -To do this the recommended tool to use is [`vcstool`](http://wiki.ros.org/vcstool) |
30 |
| -(see also https://github.com/dirk-thomas/vcstool for additional documentation and examples.). |
31 |
| - |
32 |
| -!!! note |
33 |
| - [`vcstool`](http://wiki.ros.org/vcstool) replaces [`wstool`](http://wiki.ros.org/wstool). |
34 |
| - |
35 |
| -Inside the cloned `diffbot` repository, |
36 |
| -make use of the `import` command and the `diffbot.repos` file containing the required source repositories: |
37 |
| - |
38 |
| -``` |
39 |
| -vcs import < diffbot.repos |
40 |
| -``` |
41 |
| - |
42 |
| -This will clone all repositories which are stored in the `diffbot.repos` that get passed in via stdin in YAML format. |
43 |
| - |
44 |
| -!!! note |
45 |
| - The file `diffbot.repos` contains relative paths and will clone the listed repositories in the parent folder from where |
46 |
| - the `vcs import` command is called. When it is called from inside the `diffbot` repository, which should be located |
47 |
| - in the `src` folder of a catkin workspace, then the other repositories are also cloned in the `src` folder. |
48 |
| - |
49 |
| -For the SBC not all dependencies in `diffbot.repos` are needed. |
50 |
| -Instead the `diffbot_robot.repos` is here to clone the [`rplidar_ros`](https://github.com/Slamtec/rplidar_ros) repository. |
51 |
| - |
52 |
| -``` |
53 |
| -vcs import < diffbot_robot.repos |
54 |
| -``` |
55 |
| - |
56 |
| -Now that additional packages are inside the catkin workspace it is time to install the system dependencies. |
57 |
| - |
58 |
| -### System Dependencies |
59 |
| - |
60 |
| -All the needed ROS system dependencies which are required by diffbot's packages can be installed using |
61 |
| -[`rosdep`](http://wiki.ros.org/rosdep) command, which was installed during the ROS setup. |
62 |
| -To install all system dependencies use the following command: |
63 |
| - |
64 |
| -``` |
65 |
| -rosdep install --from-paths src --ignore-src -r -y |
66 |
| -``` |
67 |
| - |
68 |
| -!!! info |
69 |
| - On the following packages pages it is explained that the dependencies of a ROS package are defined inside its `package.xml`. |
70 |
| - |
71 |
| - |
72 |
| -After the installation of all dependencies finished (which can take a while), it is time to build the catkin workspace. |
73 |
| -Inside the workspace use [`catkin-tools`](https://catkin-tools.readthedocs.io/en/latest/) to build the packages inside the `src` folder. |
74 |
| - |
75 |
| -!!! note |
76 |
| - The first time you run the following command, make sure to execute it inside your catkin workspace and not the `src` directory. |
77 |
| - |
78 |
| -``` |
79 |
| -catkin build |
80 |
| -``` |
81 |
| - |
82 |
| -Now source the catkin workspace either using the [created alias](../ros-setup.md#environment-setup) or the full command for the bash shell: |
83 |
| - |
84 |
| -``` |
85 |
| -source devel/setup.bash |
86 |
| -``` |
87 |
| - |
88 |
| -## Examples |
89 |
| - |
90 |
| -Now you are ready to follow the examples listed in the readme. |
91 |
| - |
92 |
| -!!! info |
93 |
| - TODO extend documentation with examples |
94 |
| - |
95 |
| - |
96 |
| -## Optional Infos |
97 |
| - |
98 |
| -### Manual Dependency Installation |
99 |
| - |
100 |
| -To install a package from source clone (using git) or download the source files from where they are located (commonly hosted on GitHub) into the `src` folder of a ros catkin workspace and execute the [`catkin build`](https://catkin-tools.readthedocs.io/en/latest/verbs/catkin_build.html) command. Also make sure to source the workspace after building new packages with `source devel/setup.bash`. |
101 |
| - |
102 |
| -```console |
103 |
| -cd /homw/fjp/git/diffbot/ros/ # Navigate to the workspace |
104 |
| -catkin build # Build all the packages in the workspace |
105 |
| -ls build # Show the resulting build space |
106 |
| -ls devel # Show the resulting devel space |
107 |
| -``` |
108 |
| - |
109 |
| -!!! note |
110 |
| - |
111 |
| - Make sure to clone/download the source files suitable for the ROS distribtion |
112 |
| - you are using. If the sources are not available for the distribution you are |
113 |
| - working with, it is worth to try building anyway. Chances are that the package |
114 |
| - you want to use is suitable for multiple ROS distros. For example if a package |
115 |
| - states in its docs, that it is only available for |
116 |
| - [kinetic](http://wiki.ros.org/kinetic) it is possible that it will work with a |
117 |
| - ROS [noetic](http://wiki.ros.org/noetic) install. |
| 1 | +# ROS Software Packages |
| 2 | + |
| 3 | +After having verified that the hardware requirements for the Navigation Stack are met, an |
| 4 | +overview of Remo's software follows. |
| 5 | + |
| 6 | +## Software requirements for the ROS Navigation Stack |
| 7 | + |
| 8 | +The [`diffbot`](https://github.com/ros-mobile-robots/diffbot/) and |
| 9 | +[`remo_description`](https://github.com/ros-mobile-robots/remo_description) repositories |
| 10 | +contain the following ROS packages: |
| 11 | + |
| 12 | +- `diffbot_base`: This package contains the platform-specific code for the base |
| 13 | +controller component required by the ROS Navigation Stack. It consists of the |
| 14 | +firmware based on rosserial for the Teensy MCU and the C++ node running |
| 15 | +on the SBC that instantiates the ROS Control hardware interface including the |
| 16 | +`controller_manager` control loop for the real robot. The low-level `base_controller` |
| 17 | +component reads the encoder ticks from the hardware, calculates |
| 18 | +angular joint positions and velocities, and publishes them to the ROS Control |
| 19 | +hardware interface. Using this interface makes it possible to use the `diff_drive_controller` |
| 20 | +package from [ROS Control](http://wiki.ros.org/diff_drive_controller). |
| 21 | +It provides a controller (`DiffDriveController`) for a |
| 22 | +differential drive mobile base that computes target joint velocities from commands |
| 23 | +received by either a teleop node or the ROS Navigation Stack. The computed |
| 24 | +target joint velocities are forwarded to the low-level base controller, where they are |
| 25 | +compared to the measured velocities to compute suitable motor PWM signals using |
| 26 | +two separate PID controllers, one for each motor. |
| 27 | +- `diffbot_bringup`: Launch files to bring up the hardware driver nodes (camera, |
| 28 | +lidar, microcontroller, and so on) as well as the C++ nodes from the `diffbot_base` |
| 29 | +package for the real robot. |
| 30 | +- `diffbot_control`: Configurations for `DiffDriveController` and |
| 31 | +`JointStateController` of ROS Control used in the Gazebo simulation and the |
| 32 | +real robot. The parameter configurations are loaded onto the parameter server with |
| 33 | +the help of the launch files inside this package. |
| 34 | +- `remo_description`: This package contains the URDF description of Remo |
| 35 | +including its sensors. It allows you to pass arguments to visualize different |
| 36 | +camera and SBC types. It also defines the `gazebo_ros_control` plugin. |
| 37 | +Remo's description is based on the description at https://github.com/ros-mobile-robots/mobile_robot_description, |
| 38 | +which provides a modular URDF structure that makes it easier to model your own differential drive robot. |
| 39 | +- `diffbot_gazebo`: Simulation-specific launch and configuration files for Remo |
| 40 | +and Diffbot, to be used in the Gazebo simulator. |
| 41 | +- `diffbot_msgs`: Message definitions specific to Remo/Diffbot, for example, the |
| 42 | +message for encoder data is defined in this package. |
| 43 | +- `diffbot_navigation`: This package contains all the required configuration and |
| 44 | +launch files for the ROS Navigation Stack to work. |
| 45 | +- `diffbot_slam`: Configurations for simultaneous localization and mapping using |
| 46 | +implementations such as gmapping to create a map of the environment. |
| 47 | + |
| 48 | +After this overview of the ROS packages of a differential robot that fulfill the requirements |
| 49 | +of the Navigation Stack, the next section implements the base controller component. |
| 50 | + |
| 51 | + |
| 52 | +## Developing a low-level controller and a highlevel ROS Control hardware interface for a differential drive robot |
| 53 | + |
| 54 | +In the following two sections, the base controller, mentioned in the Navigation Stack, will be developed. |
| 55 | + |
| 56 | + |
| 57 | + |
| 58 | +For Remo, this platform-specific node is split into two software components. |
| 59 | +The first component is the high-level `diffbot::DiffBotHWInterface` that |
| 60 | +inherits from `hardware_interface::RobotHW`, acting as an interface between |
| 61 | +robot hardware and the packages of ROS Control that communicate with the Navigation |
| 62 | +Stack and provide [`diff_drive_controller`](http://wiki.ros.org/diff_drive_controller) – |
| 63 | +one of many available controllers from ROS Control. With the |
| 64 | +`gazebo_ros_control` plugin, the same controller including its configuration can be |
| 65 | +used in the simulation and the real robot. An overview of ROS Control in a simulation |
| 66 | +and the real world is given in the following figure (http://gazebosim.org/tutorials/?tut=ros_control): |
| 67 | + |
| 68 | + |
| 69 | +<figure markdown> |
| 70 | +  |
| 71 | + <figcaption>ROS Control in simulation and reality</figcaption> |
| 72 | +</figure> |
| 73 | + |
| 74 | +The second component is the low-level base controller that measures angular wheel |
| 75 | +joint positions and velocities and applies the commands from the high-level interface |
| 76 | +to the wheel joints. The following figure shows the communication between the two |
| 77 | +components: |
| 78 | + |
| 79 | + |
| 80 | +<figure markdown> |
| 81 | +  |
| 82 | + <figcaption>ROS Control Simulation and Reality</figcaption> |
| 83 | +</figure> |
| 84 | + |
| 85 | +The low-level base controller uses two PID controllers to compute PWM signals for each |
| 86 | +motor based on the error between measured and target wheel velocities. |
| 87 | +`RobotHW` receives measured joint states (angular position (rad) and angular velocity |
| 88 | +(rad/s)) from which it updates its joint values. With these measured velocities and the |
| 89 | +desired command velocity (`geometry_msgs/Twist` message on the `cmd_vel` |
| 90 | +topic), from the Navigation Stack, the `diff_drive_controller` computes the |
| 91 | +target angular velocities for both wheel joints using the mathematical equations of a |
| 92 | +differential drive robot. This controller works with continuous wheel joints through a |
| 93 | +`VelocityJointInterface` class. The computed target commands are then published |
| 94 | +within the high-level hardware interface inside the robot's `RobotHW::write` method. |
| 95 | +Additionally, the controller computes and publishes the odometry on the odom topic |
| 96 | +(`nav_msgs/Odometry`) and the transform from `odom` to `base_footprint`. |
| 97 | +Having explained the two components of the base controller, the low-level firmware is |
| 98 | +implemented first. The high-level hardware interface follows the next section. |
| 99 | + |
| 100 | +!!! note "TODO" |
| 101 | + TODO Details about implementation will follow (see code for now) |
0 commit comments