Coder Social home page Coder Social logo

ros-mobile-robots / diffbot Goto Github PK

View Code? Open in Web Editor NEW
264.0 12.0 81.0 8.25 MB

DiffBot is an autonomous 2wd differential drive robot using ROS Noetic on a Raspberry Pi 4 B. With its SLAMTEC Lidar and the ROS Control hardware interface it's capable of navigating in an environment using the ROS Navigation stack and making use of SLAM algorithms to create maps of unknown environments.

Home Page: https://ros-mobile-robots.com

License: BSD 3-Clause "New" or "Revised" License

CMake 33.35% Python 0.73% Shell 1.09% C++ 60.78% Lua 2.05% C 0.39% Dockerfile 1.60%
ros diffbot robot raspberry python cpp noetic differential drive differential-drive-robot smart chassis gazebo rviz teensy navigation-stack ros-control gazebo-simulation jetson-nano robotics

diffbot's Introduction

DiffBot

CI Documentation CI

DiffBot is an autonomous differential drive robot with two wheels. Its main processing unit is a Raspberry Pi 4 B running Ubuntu Mate 20.04 and the ROS 1 (ROS Noetic) middleware. This respository contains ROS driver packages, ROS Control Hardware Interface for the real robot and configurations for simulating DiffBot. The formatted documentation can be found at: https://ros-mobile-robots.com.

DiffBot Lidar SLAMTEC RPLidar A2

If you are looking for a 3D printable modular base, see the remo_description repository. You can use it directly with the software of this diffbot repository.

Remo Gazebo Simulation RViz

It provides mounts for different camera modules, such as Raspi Cam v2, OAK-1, OAK-D and you can even design your own if you like. There is also support for different single board computers (Raspberry Pi and Nvidia Jetson Nano) through two changable decks. You are agin free to create your own.

Demonstration

SLAM and Navigation

Real robot Gazebo Simulation

📦 Package Overview

Installation

The packages are written for and tested with ROS 1 Noetic on Ubuntu 20.04 Focal Fossa. For the real robot Ubuntu Mate 20.04 for arm64 is installed on the Raspberry Pi 4 B with 4GB. The communication between the mobile robot and the work pc is done by configuring the ROS Network, see also the documentation.

Dependencies

The required Ubuntu packages are listed in software package sections found in the documentation. Other ROS catkin packages such as rplidar_ros need to be cloned into the catkin workspace.

For an automated and simplified dependency installation process install the vcstool, which is used in the next steps.

sudo apt install python3-vcstool

🔨 How to Build

To build the packages in this repository including the Remo robot follow these steps:

  1. cd into an existing ROS Noetic catkin workspace or create a new one:

    mkdir -p catkin_ws/src
  2. Clone this repository in the src folder of your ROS Noetic catkin workspace:

    cd catkin_ws/src
    git clone https://github.com/fjp/diffbot.git
  3. Execute the vcs import command from the root of the catkin workspace and pipe in the diffbot_dev.repos or remo_robot.repos YAML file, depending on where you execute the command, either the development PC or the SBC of Remo to clone the listed dependencies. Run the following command only on your development machine:

    vcs import < src/diffbot/diffbot_dev.repos
    

    Run the next command on Remo robot's SBC:

    vcs import < src/diffbot/remo_robot.repos
    
  4. Install the requried binary dependencies of all packages in the catkin workspace using the following rosdep command:

    rosdep install --from-paths src --ignore-src -r -y
    
  5. After installing the required dependencies build the catkin workspace, either with catkin_make:

    catkin_ws$ catkin_make

    or using catkin-tools:

    catkin_ws$ catkin build
  6. Finally, source the newly built packages with the devel/setup.* script, depending on your used shell:

    For bash use:

    catkin_ws$ source devel/setup.bash

    For zsh use:

    catkin_ws$ source devel/setup.zsh

Usage

The following sections describe how to run the robot simulation and how to make use of the real hardware using the available package launch files.

Gazebo Simulation with ROS Control

Control the robot inside Gazebo and view what it sees in RViz using the following launch file:

roslaunch diffbot_control diffbot.launch

This will launch the default diffbot world db_world.world.

To run the turtlebot3_world make sure to download it to your ~/.gazebo/models/ folder, because the turtlebot3_world.world file references the turtlebot3_world model. After that you can run it with the following command:

roslaunch diffbot_control diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/turtlebot3_world.world'
db_world.world turtlebot3_world.world
corridor-world turtlebot3-world

Navigation

To navigate the robot in the Gazebo simulator in db_world.world run the command:

roslaunch diffbot_navigation diffbot.launch

This uses a previously mapped map of db_world.world (found in diffbot_navigation/maps) that is served by the map_server. With this you can use the 2D Nav Goal in RViz directly to let the robot drive autonomously in the db_world.world.

DiffBot navigation

To run the turtlebot3_world.world (or your own stored world and map) use the same diffbot_navigation/launch/diffbot.launch file but change the world_name and map_file arguments to your desired world and map yaml files:

roslaunch diffbot_navigation diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/turtlebot3_world.world' map_file:='$(find diffbot_navigation)/maps/map.yaml'

DiffBot navigation

SLAM

To map a new simulated environment using slam gmapping, first run

roslaunch diffbot_gazebo diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/turtlebot3_world.world'

and in a second terminal execute

roslaunch diffbot_slam diffbot_slam.launch slam_method:=gmapping

Then explore the world with the teleop_twist_keyboard or with the already launched rqt_robot_steering GUI plugin:

DiffBot slam

When you finished exploring the new world, use the map_saver node from the map_server package to store the mapped enviornment:

rosrun map_server map_saver -f ~/map

RViz

View just the diffbot_description in RViz.

roslaunch diffbot_description view_diffbot.launch

DiffBot RViz

Navigating and Mapping on the real Robot

The following video shows how to map a new environment and navigate in it

Start by setting up the ROS Network, by making the development PC the rosmaster (set the ROS_MASTER_URI environment variable accordingly, see ROS Network Setup for more details), Then follow the steps listed below to run the real Diffbot or Remo robot hardware:

  1. First, brinup the robot hardware including its laser with the following launch file from the diffbot_bringup package. Make sure to run this on the real robot (e.g. connect to it via ssh):

    roslaunch diffbot_bringup bringup_with_laser.launch
  2. Then, in a new terminal on your remote/work development machine (not the single board computer) run the slam gmapping with the same command as in the simulation:

    roslaunch diffbot_slam diffbot_slam.launch slam_method:=gmapping

    As you can see in the video, this should open up RViz and the rqt_robot_steering plugin.

  3. Next, steer the robot around manually either using the keyboard_teleop node or using the rqt_robot_steering node and save the map with the following command when you are done exploring:

    rosrun map_server map_saver -f office

After the mapping process it is possible to use the created map for navigation, after running the following launch files:

  1. On the single board computer (e.g. Raspberry Pi) make sure that the following is launched:

    roslaunch diffbot_bringup bringup_with_laser.launch
  2. Then on the work/remote development machine run the diffbot_hw.lauch from the diffbot_navigation package:

    roslaunch diffbot_navigation diffbot_hw.lauch

    Among other essential navigation and map server nodes, this will also launch an instance of RViz on your work pc where you can use its tools to:

    1. Localize the robot with the "2D Pose Estimate" tool (green arrow) in RViz
    2. Use the "2D Nav Goal" tool in RViz (red arrow) to send goals to the robot

🚧 Future Work

Contributions to these tasks are welcome, see also the contribution section below.

ROS 2

  • Migrate from ROS 1 to ROS 2

Drivers, Odometry and Hardware Interface

  • Add diffbot_driver package for ultrasonic ranger, imu and motor driver node code.
  • Make use of the imu odometry data to improve the encoder odometry using a Kalman filter, such as robot_localization (or the less active robot_pose_ekf).
  • The current implementation of the ROS Control hardware_interface::RobotHW uses a high level PID controller. This is working but also test a low level PID on the Teensy 3.2 mcu using the Arduino library of the Grove i2c motor driver. -> This is partly implemented (see diffbot_base/scripts/base_controller) Also replace Wire.h with the improved i2c_t3 library.

Navigation

  • Test different global and local planners and add documentation
  • Add diffbot_mbf package using move_base_flex, the improved version of move_base.

Perception

To enable object detection or semantic segmentation with the RPi Camera the Raspberry Pi 4 B will be upated with a Google Coral USB Accelerator. Possible useful packages:

Mseg Example

Teleoperation

Tooling

Part List Diffbot

SBC RPi 4B MCU Teensy 3.2 IMU Bosch
Part Store
Raspberry Pi 4 B (4 Gb) Amazon.com, Amazon.de
SanDisk 64 GB SD Card Class 10 Amazon.com, Amazon.de
Robot Smart Chassis Kit Amazon.com, Amazon.de
SLAMTEC RPLidar A2M8 (12 m) Amazon.com, Amazon.de
Grove Ultrasonic Ranger Amazon.com, Amazon.de
Raspi Camera Module V2, 8 MP, 1080p Amazon.com, Amazon.de
Grove Motor Driver seeedstudio.com, Amazon.de
I2C Hub seeedstudio.com, Amazon.de
Teensy 4.0 or 3.2 PJRC Teensy 4.0, PJRC Teensy 3.2
Hobby Motor with Encoder - Metal Gear (DG01D-E) Sparkfun

Part List Remo

Part Store
Raspberry Pi 4 B (4 Gb) Amazon.com, Amazon.de
SanDisk 64 GB SD Card Class 10 Amazon.com, Amazon.de
Remo Base 3D printable, see remo_description
SLAMTEC RPLidar A2M8 (12 m) Amazon.com, Amazon.de
Raspi Camera Module V2, 8 MP, 1080p Amazon.com, Amazon.de
Adafruit DC Motor (+ Stepper) FeatherWing adafruit.com, Amazon.de
Teensy 4.0 or 3.2 PJRC Teensy 4.0, PJRC Teensy 3.2
Hobby Motor with Encoder - Metal Gear (DG01D-E) Sparkfun
Powerbank (e.g 15000 mAh) Amazon.de This Powerbank from Goobay is close to the maximum possible size LxWxH: 135.5x70x18 mm)
Battery pack (for four or eight batteries) Amazon.de

Additional (Optional) Equipment

Part Store
PicoScope 3000 Series Oscilloscope 2CH Amazon.de
VOLTCRAFT PPS-16005 Amazon.de
3D Printer for Remo's parts Prusa, Ultimaker, etc. or use a local print service or an online one such as Sculpteo

Hardware Architecture and Wiring

DiffBot

Hardware Architecture and Wiring

Remo

Hardware Architecture and Wiring

🤝 Acknowledgment

🔧 Contributing

Your contributions are most welcome. These can be in the form of raising issues, creating PRs to correct or add documentation and of course solving existing issues or adding new features.

📝 License

diffbot is licenses under the BSD 3-Clause. See also open-source-license-acknowledgements-and-third-party-copyrights.md. The documentation is licensed differently, visit its license text to learn more.

diffbot's People

Contributors

0xraks avatar fjp avatar joeuser846 avatar nielsh12 avatar pxalcantara avatar rsilverioo avatar russ76 avatar santerioksanen avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

diffbot's Issues

Initialization problem on real robot: wheels immediately start rotating after bringup

I am using "diffbot_bringup_with_laser" and I wonder why the tracks are turning? Shouldn't it wait for a navigation package to be launched? Move_base isn't running yet, is it?

This is a bug, I encounter the same problem on my robot. I suspect missing zero initializations in the diffbot_hw_interface.cpp but couldn't find the exact problem so far and didn't investiage further yet. I do set the joint states and commands to zero here in the code at the beginning but it doesn't seem to help.

Another source of this problem might be the motor driver code.

What I do to "solve" this, is to send an empty message on the /diffbot/reset topic to the encoders that might not be zero while the wheels spin. And then in my case I can stop the wheels by just blocking the wheels of the robot during this resetting, or I also make use of the motor driver reset button.

Originally posted by @fjp in #24 (comment)

Make use of rosdep for system dependencies

Test installation of the packages from this repository from scratch using rosdep (see also the documentation).

For example to see the required dependencies for a package use:

rosdep check diffbot_control
All system dependencies have been satisfied

or the verbose version in case all system dependencies are installed:

rosdep -v check diffbot_control
...
resolving for resources [diffbot_control]
resolve_all: resource [diffbot_control] requires rosdep keys [controller_manager, diff_drive_controller, hardware_interface, roscpp, rosparam_shortcuts, sensor_msgs, transmission_interface, catkin, controller_manager, joint_state_controller, robot_state_publisher, diff_drive_controller, hardware_interface, roscpp, rosparam_shortcuts, sensor_msgs, transmission_interface]
loading view [*default*] with rospkg loader
resolution: apt [ros-noetic-controller-manager, ros-noetic-diff-drive-controller, ros-noetic-hardware-interface, ros-noetic-roscpp, ros-noetic-rosparam-shortcuts, ros-noetic-sensor-msgs, ros-noetic-transmission-interface, ros-noetic-catkin, ros-noetic-joint-state-controller, ros-noetic-robot-state-publisher]
uninstalled: []
All system dependencies have been satisfied

and install the missing packages using

rosdep install AMAZING_PACKAGE

URDF model

Create a more realistic URDF model of the robot for Gazebo.

Possible workflow: Use Blender, Freecad or Google SketchUp to model the robot and convert the output to a suitable format for the URDF using MeshLab.

PID Controller

Hello,
could you please explain the values of PID controller? What is f, antiwindup, i_clampmin and i_clampmax good for?
I tried different values with no luck so far. Acceleration seems to work but when I stop the robot with a velocity of 0m/s, it starts to oscillate back and forth endless

Parametrize sensor description when using standard laser instead of gpu laser

On some platforms it is necessary to use the standard/cpu gazebo laser plugin instead of the gazebo gpu laser plugin (e.g. without dedicated gpu). Make it possible to switch between gazebo laser plugin and the gazebo gpu laser plugin and adjust the parameters (update rate, samples, ..) to avoid ghost objects:

noise-laser

See the description of turtlebot3 to avoid those issues.

Make sure to set reasonable range values to avoid hitting the robot model itself:

<range>
    <min>0.12</min>
    <max>12.0</max>
    <resolution>0.01</resolution>
  </range>

Update documentation:

Compile Grove motor driver

This task proves to be challenging. Preparing the cmakelists.txt was difficult, and now it wants libraries from the Arduino IDE before it will compile! Must the Arduino IDE be installed on the Raspberry Pi before compiling the Grove motor driver package? I copied over the two Python files that are needed from a different repo and added them to the source folder.

Python versions conflict

sudo apt-get install python-catkin-tools
Reading package lists... Done
Building dependency tree
Reading state information... Done
Some packages could not be installed. This may mean that you have
requested an impossible situation or if you are using the unstable
distribution that some required packages have not yet been created
or been moved out of Incoming.
The following information may help to resolve the situation:

The following packages have unmet dependencies:
python-catkin-tools : Depends: python (< 2.8)
Depends: python (>= 2.7)
Depends: python-catkin-pkg (>= 0.2.9) but it is not installable
Depends: python-osrf-pycommon but it is not installable
Depends: python:any (>= 2.6.6-7~)
E: Unable to correct problems, you have held broken packages.

This is what I see after trying to install Catkin tools. I followed all directions exactly up to this point.

LM393 speed sensor

Note that this sensor is deprecated in the current version of DiffBot because it isn’t a quadrature encoder.

Is there a package we can install that is quadrature enabled? Wouldn't that be better?

Russ

Issues with diffbot_gazebo diffbot_base.launch

Hi, I am trying to get the diffbot controller working in simulation. When I run the diffbot_base.launch file I see the following error:

RLException: roslaunch file contains multiple nodes named [/diffbot/robot_state_publisher]. Please check all <node> 'name' attributes to make sure they are unique. Also check that $(anon id) use different ids. The traceback for the exception was written to the log file
I can get it to run if change the name of diffbot/robot_state_publisher/ to something else such as diffbot_2/robot_state_publisher. However, I can't see the controller working in simulation. If I try to do a rostopic of encoder ticks or mesured joint states, I don't see any message being published. I see the following warning message:

WARNING: no messages received and simulated time is active. Is /clock being published?

My steps are:
roslaunch diffbot_base diffbot.launch roslaunch diffbot_gazebo diffbot_base.launch
Could you please guide me, what am I doing wrong. Thank you!

PID tuning on MCU using topics

See #13 and #35

One more thing about configurability. I am planning to use dynamic reconfigure for the PID parameters and everytime a change happens a message could be published to the low-level base controller to update its PID values. This way we could keep the performance up, because the PID runs on the microcontroller and also have configurability in the high-level code. This could be a workaround of rosserial not supporting dynamic reconfigure. But I need to check if this can actually work.

For frame [rplidar_gpu_laser_link]: Frame [rplidar_gpu_laser_link] does not exist

Hello again.

I've successfully got my RPi4 based diffbot driving around using rqt (robot steering) from my development system (Ubuntu on VirtualBox on a Mac). Now I’m trying to move to the next step and enable navigation. I start roscore on the development system and point the diffbot to it and then launch ‘bringup_with_laser.launch’ and everything seems good. I get valid looking data in /diffbot/scan on both systems.

But when I ‘roslaunch diffbot_slam diffbot_slam.launch slam_method:=gmapping’ on the development system I don’t see any lidar data points in rviz I get two errors that I don’t quite know how to interpret:

In rviz:

Transform [sender=unknown_publisher]
For frame [rplidar_gpu_laser_link]: Frame [rplidar_gpu_laser_link] does not exist

and in the terminal from which I launched diffbot_slam I get this repeating warning:

[ WARN] [1635345613.864692611]: MessageFilter [target=odom ]: Dropped 100.00% of messages so far. Please turn the [ros.gmapping.message_filter] rosconsole logger to DEBUG for more information.

Any help on why the points don’t seem to be registering in rviz would be appreciated. After a lot of googling this seems to be a TF issue perhaps? I’m a ROS newbie so I must admit I get lost in all the discussions about frames. I did check that the date/time on both systems is correctly synced to ntp.ubuntu.com but I still have the problem.

Regards,

Ian

Originally posted by @joeuser846 in #40 (comment)

Laser scan translation wrong when robot turn

slam.mp4

Hi guys,
I'm facing an issue that when I turn robot around in SLAM mode the laser scan effect was displaying wrong pose/translation, specially, its gonna fit the environment only when robot stop moving (showing in video). I'm thinking about that I got wrong odometry calculation or maybe the laser frequency update was not fast enough. This issue effected to navigation process that robot would turn into recovery mode. I didn't find the answer yet so I hope you guys could help me out.
Actually, I tried to fix this by using all same configurations with the Turtlebot3 robot but I haven't solve it yet because this issue didn't happen to this robot ://
Many thanks in advanced!

Regards,
rabbit.

Wrong wheel tire color in Gazebo

Although the color of the tire is specified as black inside the wheel.urdf.xacro URDF, its shown in yellow inside Gazebo simulation:

image

Investigate why this happens. The motor Gazeb color is working correctly, only the tire color doesn't fit.

[RViz] Reset odometry

For experiments it would be helpful to reset the odometry (x, y, orientation) back to zero. Resetting should place the robot at the same start location in RViz.

Syntax error compiling base_controller in VSCode+PIO

I've imported the base_controller project directory into VSCode+PIO. I added the Paul Stoffregen "Encoder" library but when I build I get the following syntax errors. I'd really appreciate a little guidance on what I did wrong and how to fix it. The issue seems to have something to do with namespace and scope, but exactly what? Thanks in advance for any help.

[platformio]
default_envs = teensy31
[env:teensy31]
platform = teensy
board = teensy31
framework = arduino
lib_deps =
frankjoshua/Rosserial Arduino Library@^0.9.1
./lib
adafruit/Adafruit Motor Shield V2 Library@^1.0.11
Wire
paulstoffregen/Encoder@^1.4.1

Building in release mode
Compiling .pio/build/teensy31/src/main.cpp.o
Compiling .pio/build/teensy31/lib821/SPI/SPI.cpp.o
Compiling .pio/build/teensy31/lib8c6/Ethernet/Dhcp.cpp.o
Compiling .pio/build/teensy31/lib8c6/Ethernet/Dns.cpp.o
In file included from .pio/libdeps/teensy31/lib/base_controller.h:17:0,
from src/main.cpp:4:
lib/encoder/encoder.h:39:11: error: 'Encoder' in namespace '::' does not name a type
::Encoder encoder;
^
lib/encoder/encoder.h: In member function 'int32_t diffbot::Encoder::read()':
lib/encoder/encoder.h:89:40: error: 'encoder' was not declared in this scope
inline int32_t read() { return encoder.read(); };
^
lib/encoder/encoder.h: In member function 'void diffbot::Encoder::write(int32_t)':
lib/encoder/encoder.h:97:40: error: 'encoder' was not declared in this scope
inline void write(int32_t p) { encoder.write(p); };
^

Compiling base_controller fails in VScode + PlatformIO

Hello, and thanks for an awesome project!

I am a beginner in PlatformIO, trying to compile the base_controller. My compilation fails due to:
lib/base_controller/base_controller.h:438:17: error: no matching function for call to 'ros::NodeHandle_<ArduinoHardware>::getParam(const char [28], long unsigned int*)'

I am running on Ubuntu 22.04 on top of WSL2, but am also facing the same issue on pure Ubuntu 22.04 on my laptop. I have a freshly cloned repository on both computers, and have only attempted to open and build the project in PlatformIO as advised here: https://ros-mobile-robots.com/processing_units/teensy-mcu/

Would you be able to provide any guidance on how I should proceed?

Full log from the console:

 *  Executing task: platformio run --environment teensy31 

Processing teensy31 (platform: teensy; board: teensy31; framework: arduino)
---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Verbose mode can be enabled via `-v, --verbose` option
CONFIGURATION: https://docs.platformio.org/page/boards/teensy/teensy31.html
PLATFORM: Teensy (4.18.0) > Teensy 3.1 / 3.2
HARDWARE: MK20DX256 72MHz, 64KB RAM, 256KB Flash
DEBUG: Current (jlink) External (jlink)
PACKAGES: 
 - framework-arduinoteensy @ 1.158.0 (1.58) 
 - toolchain-gccarmnoneeabi-teensy @ 1.110301.0 (11.3.1)
LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf
LDF Modes: Finder ~ chain, Compatibility ~ soft
Found 109 compatible libraries
Scanning dependencies...
Dependency Graph
|-- Rosserial Arduino Library @ 0.9.1
|-- lib @ 0.0.0+20240131183356
|-- Adafruit Motor Shield V2 Library @ 1.1.3
|-- Wire @ 1.0
|-- motor_controllers
|-- base_controller
|-- config
Building in release mode
Compiling .pio/build/teensy31/src/main.cpp.o
Archiving .pio/build/teensy31/lib2fb/libSPI.a
Indexing .pio/build/teensy31/lib2fb/libSPI.a
Archiving .pio/build/teensy31/liba29/libEthernet.a
Indexing .pio/build/teensy31/liba29/libEthernet.a
Archiving .pio/build/teensy31/lib5fe/libWire.a
Archiving .pio/build/teensy31/lib880/libAdafruit BusIO.a
Indexing .pio/build/teensy31/lib5fe/libWire.a
Indexing .pio/build/teensy31/lib880/libAdafruit BusIO.a
Archiving .pio/build/teensy31/lib189/libAdafruit Motor Shield V2 Library.a
Indexing .pio/build/teensy31/lib189/libAdafruit Motor Shield V2 Library.a
Archiving .pio/build/teensy31/lib625/libmotor_controllers.a
Archiving .pio/build/teensy31/libf57/libEncoder.a
Indexing .pio/build/teensy31/lib625/libmotor_controllers.a
Indexing .pio/build/teensy31/libf57/libEncoder.a
Archiving .pio/build/teensy31/libb01/libencoder.a
Archiving .pio/build/teensy31/lib211/libpid.a
Indexing .pio/build/teensy31/libb01/libencoder.a
Indexing .pio/build/teensy31/lib211/libpid.a
Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial1.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial2.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial3.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial4.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial5.cpp.o
In file included from src/main.cpp:4:
lib/base_controller/base_controller.h: In member function 'void diffbot::BaseController<TMotorController, TMotorDriver>::init()':
lib/base_controller/base_controller.h:438:17: error: no matching function for call to 'ros::NodeHandle_<ArduinoHardware>::getParam(const char [28], long unsigned int*)'
  438 |     nh_.getParam("/diffbot/encoder_resolution", &this->encoder_resolution_);
      |     ~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~Compiling .pio/build/teensy31/FrameworkArduino/HardwareSerial6.cpp.o
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from .pio/libdeps/teensy31/Rosserial Arduino Library/src/ros.h:38,
                 from src/main.cpp:1:
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:568:8: note: candidate: 'bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getParam(const char*, int*, int, int) [with Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]' (near match)
  568 |   bool getParam(const char* name, int* param, int length = 1, int timeout = 1000)
      |        ^~~~~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:568:8: note:   conversion of argument 2 would be ill-formed:
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:586:8: note: candidate: 'bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getParam(const char*, float*, int, int) [with Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]'
  586 |   bool getParam(const char* name, float* param, int length = 1, int timeout = 1000)
      |        ^~~~~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:586:42: note:   no known conversion for argument 2 from 'long unsigned int*' to 'float*'
  586 |   bool getParam(const char* name, float* param, int length = 1, int timeout = 1000)
      |                                   ~~~~~~~^~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:604:8: note: candidate: 'bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getParam(const char*, char**, int, int) [with Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]'
  604 |   bool getParam(const char* name, char** param, int length = 1, int timeout = 1000)
      |        ^~~~~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:604:42: note:   no known conversion for argument 2 from 'long unsigned int*' to 'char**'
  604 |   bool getParam(const char* name, char** param, int length = 1, int timeout = 1000)
      |                                   ~~~~~~~^~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:622:8: note: candidate: 'bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getParam(const char*, bool*, int, int) [with Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]'
  622 |   bool getParam(const char* name, bool* param, int length = 1, int timeout = 1000)
      |        ^~~~~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:622:41: note:   no known conversion for argument 2 from 'long unsigned int*' to 'bool*'
  622 |   bool getParam(const char* name, bool* param, int length = 1, int timeout = 1000)
      |                                   ~~~~~~^~~~~
In file included from src/main.cpp:4:
lib/base_controller/base_controller.h: In instantiation of 'diffbot::BaseController<TMotorController, TMotorDriver>::BaseController(ros::NodeHandle&, TMotorController*, TMotorController*) [with TMotorController = diffbot::AdafruitMotorController; TMotorDriver = Adafruit_MotorShield; ros::NodeHandle = ros::NodeHandle_<ArduinoHardware>]':
src/main.cpp:15:130:   required from here
lib/base_controller/base_controller.h:360:105: warning: 'diffbot::BaseController<diffbot::AdafruitMotorController, Adafruit_MotorShield>::sub_wheel_cmd_velocities_' will be initialized after [-Wreorder]
  360 |         ros::Subscriber<diffbot_msgs::WheelsCmdStamped, BaseController<TMotorController, TMotorDriver>> sub_wheel_cmd_velocities_;
      |                                                                                                         ^~~~~~~~~~~~~~~~~~~~~~~~~
lib/base_controller/base_controller.h:191:11: warning:   'diffbot::BaseController<diffbot::AdafruitMotorController, Adafruit_MotorShield>::LastUpdateTime diffbot::BaseController<diffbot::AdafruitMotorController, Adafruit_MotorShield>::last_update_time_' [-Wreorder]
  191 |         } last_update_time_;
      |           ^~~~~~~~~~~~~~~~~
lib/base_controller/base_controller.h:384:1: warning:   when initialized here [-Wreorder]
  384 | diffbot::BaseController<TMotorController, TMotorDriver>
      | ^~~~~~~
lib/base_controller/base_controller.h:191:11: warning: 'diffbot::BaseController<diffbot::AdafruitMotorController, Adafruit_MotorShield>::last_update_time_' will be initialized after [-Wreorder]
Compiling .pio/build/teensy31/FrameworkArduino/IPAddress.cpp.o
  191 |         } last_update_time_;
      |           ^~~~~~~~~~~~~~~~~
lib/base_controller/base_controller.h:146:11: warning:   'diffbot::BaseController<diffbot::AdafruitMotorController, Adafruit_MotorShield>::UpdateRate diffbot::BaseController<diffbot::AdafruitMotorController, Adafruit_MotorShield>::update_rate_' [-Wreorder]
  146 |         } update_rate_;
      |           ^~~~~~~~~~~~
lib/base_controller/base_controller.h:384:1: warning:   when initialized here [-Wreorder]
  384 | diffbot::BaseController<TMotorController, TMotorDriver>
      | ^~~~~~~
Compiling .pio/build/teensy31/FrameworkArduino/IntervalTimer.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/Print.cpp.o
In file included from .pio/libdeps/teensy31/Rosserial Arduino Library/src/ros.h:38,
                 from src/main.cpp:1:
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h: In instantiation of 'bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getParam(const char*, float*, int, int) [with Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]':
lib/base_controller/base_controller.h:441:17:   required from 'void diffbot::BaseController<TMotorController, TMotorDriver>::init() [with TMotorController = diffbot::AdafruitMotorController; TMotorDriver = Adafruit_MotorShield]'
src/main.cpp:21:25:   required from here
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:590:18: warning: comparison of integer expressions of different signedness: 'int' and 'uint32_t' {aka 'long unsigned int'} [-Wsign-compare]
  590 |       if (length == req_param_resp.floats_length)
      |           ~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h: In instantiation of 'bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getParam(const char*, bool*, int, int) [with Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]':
lib/base_controller/base_controller.h:447:17:   required from 'void diffbot::BaseController<TMotorController, TMotorDriver>::init() [with TMotorController = diffbot::AdafruitMotorController; TMotorDriver = Adafruit_MotorShield]'
src/main.cpp:21:25:   required from here
.pio/libdeps/teensy31/Rosserial Arduino Library/src/ros/node_handle.h:626:18: warning: comparison of integer expressions of different signedness: 'int' and 'uint32_t' {aka 'long unsigned int'} [-Wsign-compare]
  626 |       if (length == req_param_resp.ints_length)
      |           ~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Compiling .pio/build/teensy31/FrameworkArduino/Stream.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/Time.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/Tone.cpp.o
Compiling .pio/build/teensy31/FrameworkArduino/WMath.cpp.o
*** [.pio/build/teensy31/src/main.cpp.o] Error 1```

Robot not moving straight because of different friction in motor gears

The odometry updates are working after the use of wheel joint delta angles to update the joint positions in the hardware interface (see the code here). However there is a problem when simply mapping the velocity command from the diff_drive_controller to the power output percentage for the motor driver in the RobotHW::write(). The robot is not moving straight, its moving slightly to the left. This is because one of the motors (the one on the left side) seems to have slightly higher internal gear friction. I have created a video to show this behaviour.

diff_drive_controller cannot solve this problem because it is only forwarding the /cmd_vel command: see its code here so it is not taking care whether the encoder ticks increase on one wheel but not the other.

As seen in the video possible solutions are:

  1. Use better hardware, more precise motors in this case - not really an option for me because I would like to keep using the current motors.
  2. Calibrate the motors in code using threshold/tolerance offset values to provide slightly different outputs to the motors, so that they move and stop at the same time.
  3. Implement a PID controller inside the high level DiffBot's RobotHW::write() method or in the low level motor driver node, something like u=k*(v_actual - v_target)? This should apply the correct amount of output power to a motor depending on the actual velocity error on the wheel joint. ROS Control expects that the commands coming from a controller such as diff_drive_controller (velocity command) must be applied at the actuators.

To get the robot driving straight are there other ways other than the ones mentioned above and which one should be used to solve the issue? I prefer the PID controller, because it seems to solve the problem with less code. I tried the 2nd option but it seems that a lot of if else cases or even a simple state machine are needed for this. And in case of the 3rd option where should the PID be implemented? In the high level hardware interface RobotHW::write() or the low level motor driver.py node? Currently I would put it in the high level hw interface because all the joint velocities (actual and desired) are already calculated there. But having it in the motor driver node seems also correct, although this will require at least another subscriber in this node or re-writing it so that it subscribes to the commanded and measured velocity.

Any suggestions are more than welcome.

Mismatched protocol version in packet (b'\xff'): lost sync or rosserial_python is from different ros release than the rosserial client

When using two publisher (pub_measured_joint_states_ and pub_encoders_ in the void diffbot::BaseController<TMotorController, TMotorDriver>::read() method, the following error can occur:

[ERROR] [1642866871.814281]: Mismatched protocol version in packet (b'\xff'): lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [1642867178.756300]: Protocol version of client is Rev 0 (rosserial 0.4 and earlier), expected Rev 1 (rosserial 0.5+)

and

[INFO] [1642867191.950343]: wrong checksum for topic id and msg

Suggestions in this answer might help

  • lowering baud rate
  • Don't use Serial.print and rosserial

Possible other solutions:

  • Edit ros::NodeHandle number of publisher, subscriber and buffer input/output sizes explained in ros wiki
  • Add delay between publish commands (not preferred)
  • publish at different rates (not optimal, only fallback solution)

Single Board Computer I2C Connection

Hi Franz,
I find it a bit confusing that the MCU is going to handle the Motor encoder and also Actuation. The MCU should be receiving commands and possibly sending sensory readings to the SBC as shown here https://ros-mobile-robots.com/fritzing/remo_architecture.svg

While going through the Hardware Interfaces section, I found that the SBC needs to communicate with the motor driver. This contradicts the figure shown here https://ros-mobile-robots.com/fritzing/remo_architecture.svg

This brings some ambiguity that how to connect all the hardware for minimal testing at the first place.

Best.....

Question about Motors, minimum accomplishable RPM

Hello,

I am using the same type of motors, and a custom made driver board for my robot. Everything is working well, but there is a minor problem: These motors have a high deadzone, and the PID algorithm is having a hard time - controlling them at low speeds, such as < 5RPM. The problem gets worse, as the robot weight increases. :(

I have tried many things, such as lowering the PWM frequency, (the lower the pwm frequency, the less deadzone we have, but at frequencies like 100hz, the system generates electrical noise. Another trick that I tried is to read encoders, and current feedback and change pid constants when the motor is not moving, which does work - but then leads to stability problems in the PID algorithm.

What was your experience on this problem? What was your lowest observed wheel RPM? I understand you are doing the PID in the teensy, and not doing something non-standard?

Best Regards,
Can Altineller

wheel_radius problem

Hi,
I use diffbot package on my robot. I revised the parameters according to my own robot. But i have a problem. If I set the wheel_radius parameter to 1, all the values are correct, but if I set it to its real value for wheel_radius, the odom and desired_position datas are corrupted.
How can i fix this problem?
Thank you

Encoder data in simulation

Hi, great work. I have a question: is there an implementation of the encoder data also on the simulation? Because I can't find it.

IMU code

Where is the code that includes the IMU?

PID min_val and max_val

Can anyone tell me where min_val and max_val are declared ?
When declaring motor_pid_left_ and motor_pid_right_, I see that we are not passing these values?

PID motor_pid_left_;
PID motor_pid_right_;

In my motor driver, I need to set the output limits to -30000 to 0 and 0 to 30000. So I'm trying to change these limits. I tried the map function, but it did not work well. Any help is appreciated. Thanks!

Motors don't turn

Cannot get the motors to run from the joystick. I checked, and it is publishing data to /diffbot/mobile_base_controller/cmd_vel. Also the /diffbot/wheel_cmd_velocities shows data from the joystick. But /motor_left and /motor_right do not show any data. If I send a command from CLI on that topic then the motors will run. I am running joy and teleop_twist_joy on the laptop. And I ran the launch file on robot called roslaunch diffbot_bringup bringup.launch

I am using the Python Grove motor controller routines. I don't have the Lidar tested yet; was saving that for after the driving was proven. The encoders seem to work correctly. The odom topic stays at zero, even when tracks are spun by hand. I tried using the rqt_robot_steering and it published but no response from program or motors.

I'm using Raspi 4.0 with 4 Gig, Ubuntu 20.04 Mate and Noetic.

What should I try next to fix this robot?

pi@raspberrypi:~$ roswtf
Loaded plugin tf.tfwtf
No package or stack in the current directory
================================================================================
Static checks summary:

No errors or warnings
================================================================================
Beginning tests of your ROS graph. These may take a while...
analyzing graph...
... done analyzing graph
running graph rules...
... done running graph rules
running tf checks, this will take a second...
... tf checks complete

Online checks summary:

Found 1 warning(s).
Warnings are things that may be just fine, but are sometimes at fault

WARNING The following node subscriptions are unconnected:
 * /diffbot/mobile_base_controller/joy_node:
   * /diffbot/mobile_base_controller/joy/set_feedback
 * /motor_driver:
   * /motor_left
   * /motor_right
 * /diffbot/diffbot_base:
   * /diffbot/measured_joint_states


Found 1 error(s).

ERROR The following nodes should be connected but aren't:
 * /diffbot/rosserial_base_controller->/diffbot/diffbot_base (/diffbot/encoder_ticks)
pi@raspberrypi:~$ roslaunch diffbot_bringup bringup.launch
... logging to /home/pi/.ros/log/ac5e6b76-6f8c-11ed-bbf4-d981b5fb025a/roslaunch-raspberrypi-2589.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://raspberrypi:37209/

SUMMARY
========

PARAMETERS
 * /diffbot/debug/base_controller: True
 * /diffbot/debug/hardware_interface: False
 * /diffbot/encoder_resolution: 542
 * /diffbot/gain: 1.0
 * /diffbot/hardware_interface/joints: ['front_left_whee...
 * /diffbot/joint_state_controller/extra_joints: [{'name': 'rear_c...
 * /diffbot/joint_state_controller/publish_rate: 50
 * /diffbot/joint_state_controller/type: joint_state_contr...
 * /diffbot/mobile_base_controller/angular/z/has_acceleration_limits: True
 * /diffbot/mobile_base_controller/angular/z/has_velocity_limits: True
 * /diffbot/mobile_base_controller/angular/z/max_acceleration: 6.0
 * /diffbot/mobile_base_controller/angular/z/max_velocity: 8.0
 * /diffbot/mobile_base_controller/base_frame_id: base_footprint
 * /diffbot/mobile_base_controller/left_wheel: front_left_wheel_...
 * /diffbot/mobile_base_controller/linear/x/has_acceleration_limits: True
 * /diffbot/mobile_base_controller/linear/x/has_velocity_limits: True
 * /diffbot/mobile_base_controller/linear/x/max_acceleration: 0.6
 * /diffbot/mobile_base_controller/linear/x/max_velocity: 0.3
 * /diffbot/mobile_base_controller/pose_covariance_diagonal: [0.001, 0.001, 0....
 * /diffbot/mobile_base_controller/publish_rate: 50
 * /diffbot/mobile_base_controller/right_wheel: front_right_wheel...
 * /diffbot/mobile_base_controller/twist_covariance_diagonal: [0.001, 0.001, 0....
 * /diffbot/mobile_base_controller/type: diff_drive_contro...
 * /diffbot/mobile_base_controller/wheel_radius: 0.0325
 * /diffbot/mobile_base_controller/wheel_separation: 0.145
 * /diffbot/motor_constant: 1.0
 * /diffbot/pwm_limit: 1.0
 * /diffbot/robot_description: <?xml version="1....
 * /diffbot/trim: 0.0
 * /rosdistro: noetic
 * /rosversion: 1.15.14

NODES
  /diffbot/
    controller_spawner (controller_manager/spawner)
    diffbot_base (diffbot_base/diffbot_base)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    rosserial_base_controller (rosserial_python/serial_node.py)

ROS_MASTER_URI=http://192.168.1.149:11311

process[diffbot/rosserial_base_controller-1]: started with pid [2599]
process[diffbot/diffbot_base-2]: started with pid [2600]
process[diffbot/controller_spawner-3]: started with pid [2601]
process[diffbot/robot_state_publisher-4]: started with pid [2602]
[ INFO] [1669688872.159374857]: Waiting for model URDF on the ROS param server at location: /diffbot/diffbot/robot_description
[ INFO] [1669688872.458654923]: mobile_base_controller/wheel_radius: 0.0325
[ INFO] [1669688872.459160499]: mobile_base_controller/linear/x/max_velocity: 9.23077
[ INFO] [1669688872.459535815]: encoder_resolution: 542
[ INFO] [1669688872.459898835]: gain: 1
[ INFO] [1669688872.460260207]: trim: 0
[ INFO] [1669688872.460684153]: motor_constant: 1
[ INFO] [1669688872.461061506]: pwm_limit: 1
[ INFO] [1669688872.587988059]: Initializing DiffBot Hardware Interface ...
[ INFO] [1669688872.588351449]: Number of joints: 2
[ INFO] [1669688872.588831932]: pid namespace: pid/left_motor
[ INFO] [1669688872.589166600]: Initialize PID
[ INFO] [1669688872.589441823]: Initializing dynamic reconfigure in namespace /diffbot/pid/left_motor
[ INFO] [1669688873.155046982]: Update PID Gains: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-9.23077, out_max=9.23077
[INFO] [1669688873.232623]: ROS Serial Python Node
[INFO] [1669688873.240327]: Controller Spawner: Waiting for service controller_manager/load_controller
[ INFO] [1669688873.364933075]: Initialized dynamic reconfigure
[ INFO] [1669688873.365176335]: Initialized PID: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-9.23077, out_max=9.23077
[ INFO] [1669688873.365339206]: Update PID output limits: lower=9.23077, upper=-9.23077
[ INFO] [1669688873.365568207]: pid namespace: pid/right_motor
[ INFO] [1669688873.365807170]: Initialize PID
[ INFO] [1669688873.365938301]: Initializing dynamic reconfigure in namespace /diffbot/pid/right_motor
[INFO] [1669688873.642192]: Connecting to /dev/ttyACM0 at 115200 baud
[ INFO] [1669688873.778586700]: Update PID Gains: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-9.23077, out_max=9.23077
[ INFO] [1669688873.833593473]: Initialized dynamic reconfigure
[ INFO] [1669688873.833895419]: Initialized PID: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-9.23077, out_max=9.23077
[ INFO] [1669688873.834055067]: Update PID output limits: lower=9.23077, upper=-9.23077
[ INFO] [1669688873.835291757]: ... Done Initializing DiffBot Hardware Interface
[ INFO] [1669688873.835604351]: Get number of measured joint states publishers
[ INFO] [1669688873.835764814]: Waiting for measured joint states being published...
[INFO] [1669688875.782482]: Requesting topics...
[INFO] [1669688875.836128]: Note: publish buffer size is 512 bytes
[INFO] [1669688875.849856]: Setup publisher on encoder_ticks [diffbot_msgs/Encoders]
[WARN] [1669688876.089304]: Could not process inbound connection: topic types do not match: [diffbot_msgs/EncodersStamped] vs. [diffbot_msgs/Encoders]{'callerid': '/diffbot/diffbot_base', 'md5sum': '162975f999a4d19c3bdc0165594516da', 'tcp_nodelay': '0', 'topic': '/diffbot/encoder_ticks', 'type': 'diffbot_msgs/EncodersStamped'}
[INFO] [1669688876.100320]: Setup publisher on imu/data_raw [sensor_msgs/Imu]
[INFO] [1669688876.137299]: Note: subscribe buffer size is 512 bytes
[INFO] [1669688876.148397]: Setup subscriber on reset [std_msgs/Empty]
[INFO] [1669688876.167773]: Initialize DiffBot Wheel Encoders
[INFO] [1669688876.189302]: Reset both wheel encoders to zero
[ERROR] [1669688883.847392374]: No measured joint states publishers. Timeout reached.
[ INFO] [1669688883.847636764]: Publish /reset to encoders
[INFO] [1669688883.870655]: Reset both wheel encoders to zero
[INFO] [1669688884.094214]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1669688884.129574]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1669688884.159781]: Loading controller: joint_state_controller
[INFO] [1669688884.318724]: Loading controller: mobile_base_controller
[ INFO] [1669688884.394240071]: Controller state will be published at 50Hz.
[ INFO] [1669688884.405349795]: Wheel separation will be multiplied by 1.
[ INFO] [1669688884.423917861]: Left wheel radius will be multiplied by 1.
[ INFO] [1669688884.424095640]: Right wheel radius will be multiplied by 1.
[ INFO] [1669688884.430501959]: Velocity rolling window size of 10.
[ INFO] [1669688884.436123349]: Velocity commands will be considered old if they are older than 0.5s.
[ INFO] [1669688884.441565201]: Allow mutiple cmd_vel publishers is enabled
[ INFO] [1669688884.456231920]: Base frame_id set to base_footprint
[ INFO] [1669688884.464825191]: Odometry frame_id set to odom
[ INFO] [1669688884.470855472]: Publishing to tf is enabled
[ INFO] [1669688884.662570169]: Odometry params : wheel separation 0.145, left wheel radius 0.0325, right wheel radius 0.0325
[ INFO] [1669688884.689471339]: Adding left wheel with joint name: front_left_wheel_joint and right wheel with joint name: front_right_wheel_joint
[ INFO] [1669688884.848075530]: Dynamic Reconfigure:
DynamicParams:
	Odometry parameters:
		left wheel radius multiplier: 1
		right wheel radius multiplier: 1
		wheel separation multiplier: 1
	Publication parameters:
		Publish executed velocity command: disabled
		Publication rate: 50
		Publish frame odom on tf: enabled
[INFO] [1669688884.918523]: Controller Spawner: Loaded controllers: joint_state_controller, mobile_base_controller
[INFO] [1669688885.018769]: Started controllers: joint_state_controller, mobile_base_controller
pi@raspberrypi:~$ rostopic list -v

Published topics:
 * /rosout [rosgraph_msgs/Log] 7 publishers
 * /rosout_agg [rosgraph_msgs/Log] 1 publisher
 * /diagnostics [diagnostic_msgs/DiagnosticArray] 2 publishers
 * /diffbot/mobile_base_controller/joy [sensor_msgs/Joy] 1 publisher
 * /diffbot/mobile_base_controller/cmd_vel [geometry_msgs/Twist] 1 publisher
 * /tf [tf/tfMessage] 2 publishers
 * /tf_static [tf2_msgs/TFMessage] 1 publisher
 * /diffbot/motor_left [std_msgs/Int32] 1 publisher
 * /diffbot/motor_right [std_msgs/Int32] 1 publisher
 * /diffbot/wheel_cmd_velocities [diffbot_msgs/WheelsCmdStamped] 1 publisher
 * /diffbot/reset [std_msgs/Empty] 1 publisher
 * /diffbot/pid/left_motor/parameter_descriptions [dynamic_reconfigure/ConfigDescription] 1 publisher
 * /diffbot/pid/left_motor/parameter_updates [dynamic_reconfigure/Config] 1 publisher
 * /diffbot/pid/right_motor/parameter_descriptions [dynamic_reconfigure/ConfigDescription] 1 publisher
 * /diffbot/pid/right_motor/parameter_updates [dynamic_reconfigure/Config] 1 publisher
 * /diffbot/encoder_ticks [diffbot_msgs/Encoders] 1 publisher
 * /diffbot/imu/data_raw [sensor_msgs/Imu] 1 publisher
 * /diffbot/joint_states [sensor_msgs/JointState] 1 publisher
 * /diffbot/mobile_base_controller/odom [nav_msgs/Odometry] 1 publisher
 * /diffbot/mobile_base_controller/parameter_descriptions [dynamic_reconfigure/ConfigDescription] 1 publisher
 * /diffbot/mobile_base_controller/parameter_updates [dynamic_reconfigure/Config] 1 publisher

Subscribed topics:
 * /rosout [rosgraph_msgs/Log] 1 subscriber
 * /diffbot/mobile_base_controller/joy/set_feedback [sensor_msgs/JoyFeedbackArray] 1 subscriber
 * /diffbot/mobile_base_controller/joy [sensor_msgs/Joy] 1 subscriber
 * /motor_left [std_msgs/Int32] 1 subscriber
 * /motor_right [std_msgs/Int32] 1 subscriber
 * /diffbot/joint_states [sensor_msgs/JointState] 1 subscriber
 * /diffbot/encoder_ticks [diffbot_msgs/Encoders] 1 subscriber
 * /diffbot/measured_joint_states [sensor_msgs/JointState] 1 subscriber
 * /diffbot/reset [std_msgs/Empty] 1 subscriber
 * /diffbot/mobile_base_controller/cmd_vel [geometry_msgs/Twist] 1 subscriber

ROS Control Hardware Interface

ROS Control provides the diff_drive_controller package, which is useful to simulate the robot in Gazebo.

For the real robot it is required to write a hardware interface in C++ to leverage the diff_drive_controller package.

No output for wheel_cmd_velocities? [Question - Closed]

First of all: amazing repo! Absolutely great work!

I was launching the navigation and base via

roslaunch diffbot_base  diffbot.launch
roslaunch diffbot_navigation diffbot.launch

to get a more in-depth understanding of ros_control, specifically the hardware_interface's write function. Luckily, the functions published the diff_drive_controller's output (which it received via the joint_velocity_commands_)

When I assign a drive command (e.g. angular velocity), the Gazebo Simulation works perfectly fine and the robot is spinning. However, the /diffbot/wheel_cmd_velocities yield only zero.

As seen in the screenshot below, only zeros are yielded if I run both (which makes sense, since the base is not connected to the cmd velocity, as seen in the node graph)

Screenshot from 2023-02-13 15-10-14

Edit: if I run diffbot_base diffbot.launch (without diffbot_navigation diffbot.launch), I receive the expected output)

Screenshot from 2023-02-13 16-03-07

Therefore, my question: Is it even POSSIBLE to run both, the navigation in gazebo AND the hardware_interface?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.