ros-mobile-robots / diffbot

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.
https://ros-mobile-robots.com
BSD 3-Clause "New" or "Revised" License
275 stars 82 forks source link

LM393 speed sensor #24

Open Russ76 opened 3 years ago

Russ76 commented 3 years ago

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

fjp commented 3 years ago

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

That's true

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

No, not directly a package on its own currently. The code for the encoders is running on the Teensy 4.0 (or 3.2) microcontroller. This script is part of the diffbot_base package. Please note that I am using the Encoder Library available on Arduino/Teensy boards. But I guess this should also work on other microcontroller boards.

Russ76 commented 3 years ago

I believe the hardware on my "tank" is quadrature, so I'll try to get software to match that. My previous robot didn't have that, and it caused problems moving backward.

fjp commented 3 years ago

I fully agree with you on quadrature encoders and my last comment missed that point a bit. As you mentioned, it is possible to read the direction using quadrature encoders and the motors that I use DG01D-E have one built inside. As far as I am aware, the Teensy Encoder lib that I use makes use of quadrature encoders: counting both edges (rising and falling) on both channels to make use of the counts per revolution (CPR) and therefore yield a high resolution.

image source

Unfortunately I don't know if there exist a specific ROS package for quadrature encoders already but it would be interesting to know.

Russ76 commented 3 years ago

I see, it is just your hardware that isn't quad, the software is capable! That is good to know. I will continue to install the software.

Russ76 commented 3 years ago

Seems like that would be best, to let the Teensy deal with the ticks and free up the Raspberry to deal with cameras and navigation and communications. At this point, (in your documentation) the Raspberry is wired with I2C connections to encoders. I don't understand how the Teensy also deals with this counting?

fjp commented 3 years ago

I see, it is just your hardware that isn't quad, the software is capable! That is good to know. I will continue to install the software.

The ones I use are also quadrature encoders. So I can confirm that it works with the software that I use :-)

Seems like that would be best, to let the Teensy deal with the ticks and free up the Raspberry to deal with cameras and navigation and communications.

Exactly, on the Teensy I also make use of hardware interrupts (done by the Teensy Encoder Library).

At this point, (in your documentation) the Raspberry is wired with I2C connections to encoders. I don't understand how the Teensy also deals with this counting?

This is not the case, otherwise the documentation is wrong. The two "Hall effect pins" (H1 and H2) of each encoder are directly connected to hardware interrupt capable pins on the Teensy. This is documented here but I should add the schematic showing how it is done. I hope to finish that soon.

Russ76 commented 3 years ago

From: https://fjp.at/projects/diffbot/hardware-interfaces/

The LM393 speed sensors also use a single digital GPIO pin each. These pins will be setup using software interrupts with the RPi.GPIO library. Prepare I2C ConnectionPermalink The I2C connections are used for multiple components such as the motor driver and the oled display. Using these ports on the Raspberry Pi 4 B, requires that we enable the I2C interface.

fjp commented 3 years ago

Thank you! That part of the docs, regarding the LM393 speed sensors, is outdated. Also I don't use software interrupts. Now that you showed me I will update it :-)

But it is true that the Grove I2C Motor Driver is connected via I2C to the Rasperry Pi. This motor driver powers the two motors (M+, M-). However, the encoders (H1, H2) are directly connected to the pins on the Teensy, hence no I2C used for them.

Russ76 commented 3 years ago

I checked into the Grove I2C motor driver but it was out-of-stock. I got an Ardumoto from SparkFun. But I figured out that their sample program for controlling it was incorrect. They tried to use just one sense line to change direction of motor, and two are required by the L298. In the "spin" portion of the code, they happened to send the two, and the robot will spin, but they failed to note that in the other segments, forward and reverse were not operating properly. In2 and In4 are also needed, and are not wired to the edge of the board, but are accessible in the center portion. I will use the Teensy to drive the Ardumoto board and this should work. Thanks for your guidance!

Russ76 commented 3 years ago

Franz, I wonder if you forgot to include the header file for the Teensy encoder program? https://github.com/PaulStoffregen/Encoder/blob/master/Encoder.h This is a long one, and includes assembly language, too.

fjp commented 3 years ago

Hi Russ, yes you are right I didn't include the Encoder.h header from the Teensy Encoder library explicitly in my repository. But I am making use of it. When building the Encoder script of this repository it will get linked/included. To make this more clear how it is done: After installing the Teensyduino addon for the Arduino IDE (please see the docs here for more details) you the Encoder library is "ready to use" and can the header can simply be included. This is more or less what I have written briefly here in the docs. I agree this part can also be improved.

Now after you raised this question I am thinking of including the Teensy Encoder library, because as this would make the (next) tag more robust to changes in the Encoder library. I think this is what Linorobot did and it seems that he includes the whole rosserial library too, which I also don't do currently.

On the other hand I am not really a fan of copying complete code sections from another source, because this will likely lead to missing updates in the external libraries. However, to cope with braking upstream changes, I think it would be better to state which tag of the external library/dependency was used or is needed in order to build a specific tag.

I think I will go this way, and add the exact version of the rosserial lib and the Teensy Encoder library to the documentation and also add a comment into the Encoder script of my repository.

Russ76 commented 3 years ago

That is interesting, I didn't know it was already included! That makes it easier, yes. What about the switch for Teensy, making it faster:

define ENCODER_OPTIMIZE_INTERRUPTS // comment this out on Non-Teensy boards

include "Encoder.h"

I may have to test this and see if it works with Diffbot code.

fjp commented 3 years ago

That is interesting, I didn't know it was already included! That makes it easier, yes.

Yes implicitly the library dependency is available and I think that this makes this repository's code base more light weight.

What about the switch for Teensy, making it faster:

define ENCODER_OPTIMIZE_INTERRUPTS // comment this out on Non-Teensy boards

include "Encoder.h"

I may have to test this and see if it works with Diffbot code.

Yes that would be a great addition and would be interesting to know more about results! From the specific section in the encoder library documentation: https://www.pjrc.com/teensy/td_libs_Encoder.html#optimize it seems that this will make the code perform faster on Teensy/Arduino boards.

In case you are interested and have the time I would also welcome a PR on this.

But I would also add a comment about the possible downside mentioned in the docs:

Encoder will directly define interrupts the minimum overhead. The downside is a conflict if any other code in your sketch or any libraries you use require attachInterrupt().

Russ76 commented 3 years ago

arduino-1.8.13/hardware/teensy/avr/cores/teensy3" -I/home/rodolfo/Arduino/libraries/Rosserial_Arduino_Library/src /tmp/arduino_build_863282/sketch/sketch_feb20a.ino.cpp -o /dev/null -DARDUINO_LIB_DISCOVERY_PHASE Alternatives for diffbot_msgs/Encoder.h: [] ResolveLibrary(diffbot_msgs/Encoder.h) -> candidates: [] /home/rodolfo/Arduino/sketch_feb20a/sketch_feb20a.ino:28:34: fatal error: diffbot_msgs/Encoder.h: No such file or directory compilation terminated. Using library Rosserial_Arduino_Library at version 0.9.1 in folder: /home/rodolfo/Arduino/libraries/Rosserial_Arduino_Library Error compiling for board Teensy 3.2 / 3.1.

Russ76 commented 3 years ago

I copied the file Encoder.h from "Build" under Catkin_ws, and put it into a folder named "diffbot_msgs" under libraries, under Arduino. Seems the Arduino IDE isn't happy with this.

fjp commented 3 years ago

Copying the Encoder.h shouldn't be needed to build the diffbot_base/scripts/encoders/encoders/encoders.ino script.

What I would try first is to check if the Encoder.h is usable by trying to compile an example in the Arduino IDE that uses the Encoder.h. For example I tried the TwoKnobs from the Teensy library. It should be located here: File > Examples > Encoder > TwoKnobs after intalling the Teensyduino.

Russ76 commented 3 years ago

Yes, that example does compile. The other doesn't because of diffbot/encoder.msg

fjp commented 3 years ago

Ok sounds good if that is working. Now regarding the diffbot/encoder.msg, what worked for me was using rosrun rosserial_client make_libraries ~/Arduino/tmp/ and then copy the result from this script to the arduino library folder.

I documented it here: https://fjp.at/diffbot/diffbot_msgs/#using-rosmsg and it is basically from the official documentation here: http://wiki.ros.org/rosserial/Tutorials/Adding%20Other%20Messages

Russ76 commented 3 years ago

Sounds good. I will get to work on this in 24 hours.

Russ76 commented 3 years ago

I got it to recognize and load Encoder.h Now it complains about something within the file!

ResolveLibrary(ros/types.h) -> candidates: [] In file included from /home/rodolfo/Arduino/sketch_feb20a/sketch_feb20a.ino:28:0: /home/rodolfo/Arduino/libraries/Rosserial_Arduino_Library/src/std_msgs/Encoder.h:13:23: fatal error: ros/types.h: No such file or directory compilation terminated. Using library Rosserial_Arduino_Library at version 0.9.1 in folder: /home/rodolfo/Arduino/libraries/Rosserial_Arduino_Library Error compiling for board Teensy 3.2 / 3.1. Invalid library found in /home/rodolfo/Arduino/libraries/ros_lib: no headers files (.h) found in /home/rodolfo/Arduino/libraries/ros_lib

fjp commented 3 years ago

There might be a confusion with Encoder.h of the Teensy encoder library and the diffbot_msgs/Encoder.h that we have to generate using the mentioned rosserial command. Or the wrong rosserial library is used.

Can you confirm that your rosserial_library in the Arduino libraries folder contains the diffbot_msgs package?

This is what I get when compiling the encoders.ino:

image

Another issue that might cause your compiler error is a rosserial lib that is too old. I am using the latest tag from github: https://github.com/frankjoshua/rosserial_arduino_lib/tree/0.9.1

There might be even two ros_serial libraries inside your Arduino/libraries folder. The one you can download with the Libraries Manager and the latest one.

I agree this is not enough documented on my side. I hope the above can still help you but I will also look into this again and try to provide a better workflow to get this working.

fjp commented 3 years ago

Here are some more insights on how the arduino rosserial library looks for me: In my home folder /home/fjp/Arduino/libraries/ I have installed the latest tag of the rosserial_arduino_lib (https://github.com/frankjoshua/rosserial_arduino_lib/tree/0.9.1) and the tree -d command inside the libraries folder command gives me this:

libraries$ tree -d
.
... other libraries truncated ...
├── Rosserial_Arduino_Library
│   ├── examples
│   │   ├── ADC
│   │   ├── Blink
│   │   ├── BlinkerWithClass
│   │   ├── BlinkM
│   │   ├── button_example
│   │   ├── Clapper
│   │   ├── Esp8266
│   │   ├── Esp8266HelloWorld
│   │   ├── HelloWorld
│   │   ├── IrRanger
│   │   ├── Logging
│   │   ├── Odom
│   │   ├── pubsub
│   │   ├── ServiceClient
│   │   ├── ServiceServer
│   │   ├── ServoControl
│   │   ├── TcpBlink
│   │   ├── TcpHelloWorld
│   │   ├── Temperature
│   │   ├── TimeTF
│   │   └── Ultrasound
│   ├── extras
│   │   └── tests
│   │       ├── array_test
│   │       ├── float64_test
│   │       └── time_test
│   ├── scripts
│   └── src
│       ├── actionlib
│       ├── actionlib_msgs
│       ├── actionlib_tutorials
│       ├── bond
│       ├── controller_manager_msgs
│       ├── control_msgs
│       ├── control_toolbox
│       ├── diagnostic_msgs
│       ├── diffbot_msgs
│       ├── dynamic_reconfigure
│       ├── gazebo_msgs
│       ├── geometry_msgs
│       ├── gps_common
│       ├── laser_assembler
│       ├── map_msgs
│       ├── nav_msgs
│       ├── nodelet
│       ├── pcl_msgs
│       ├── polled_camera
│       ├── ros
│       ├── roscpp
│       ├── roscpp_tutorials
│       ├── rosgraph_msgs
│       ├── rospy_tutorials
│       ├── rosserial_arduino
│       ├── rosserial_mbed
│       ├── rosserial_msgs
│       ├── sensor_msgs
│       ├── shape_msgs
│       ├── smach_msgs
│       ├── std_msgs
│       ├── std_srvs
│       ├── stereo_msgs
│       ├── tf
│       ├── tf2_msgs
│       ├── theora_image_transport
│       ├── topic_tools
│       ├── trajectory_msgs
│       ├── turtle_actionlib
│       ├── turtlesim
│       └── visualization_msgs
... further libraries truncated ...

Please notice the diffbot_msgs package in the src folder. This has the Encoder.h with the custom message definition.

Russ76 commented 3 years ago

Yes, it could be an issue of different versions. On my laptop I have Melodic, and on the Raspi, Noetic. I am attempting to program the Teensy from the laptop. Maybe the Arduino IDE works on the Raspi? Earlier, I found that the Arduino IDE didn't run on the Nvidia TX1. Thanks for your patience!

Russ76 commented 3 years ago

Making progress! This much could run in Rviz and Gazebo: roslaunch diffbot_control diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/corridor.world' ... logging to /home/rod/.ros/log/3809b1b8-7579-11eb-99a1-f17e41f2f6b1/roslaunch-rod-raspi-25719.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://localhost:46705/

SUMMARY

PARAMETERS

NODES / gazebo (gazebo_ros/gzserver) gazebo_gui (gazebo_ros/gzclient) rqt_robot_steering (rqt_robot_steering/rqt_robot_steering) rviz (rviz/rviz) urdf_spawner (gazebo_ros/spawn_model) /diffbot/ controller_spawner (controller_manager/spawner) robot_state_publisher (robot_state_publisher/robot_state_publisher)

auto-starting new master process[master]: started with pid [25730] ROS_MASTER_URI=http://localhost:11311

setting /run_id to 3809b1b8-7579-11eb-99a1-f17e41f2f6b1 process[rosout-1]: started with pid [25740] started core service [/rosout] process[gazebo-2]: started with pid [25747] process[gazebo_gui-3]: started with pid [25751] process[urdf_spawner-4]: started with pid [25756] process[diffbot/controller_spawner-5]: started with pid [25758] process[diffbot/robot_state_publisher-6]: started with pid [25759] process[rqt_robot_steering-7]: started with pid [25760] process[rviz-8]: started with pid [25761] [INFO] [1614044912.576562, 0.000000]: Controller Spawner: Waiting for service controller_manager/load_controller [INFO] [1614044913.312827, 0.000000]: Loading model XML from ros parameter /diffbot/robot_description [INFO] [1614044913.359322, 0.000000]: Waiting for service /gazebo/spawn_urdf_model [gazebo-2] process has died [pid 25747, exit code 255, cmd /opt/ros/noetic/lib/gazebo_ros/gzserver -e ode /home/rod/ros_ws/src/diffbot/diffbot_gazebo/worlds/corridor.world name:=gazebo log:=/home/rod/.ros/log/3809b1b8-7579-11eb-99a1-f17e41f2f6b1/gazebo-2.log]. log file: /home/rod/.ros/log/3809b1b8-7579-11eb-99a1-f17e41f2f6b1/gazebo-2.log [ INFO] [1614044916.267720607]: Finished loading Gazebo ROS API Plugin. [ INFO] [1614044916.284697810]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting... [WARN] [1614044942.865821, 0.000000]: Controller Spawner couldn't find the expected controller_manager ROS interface. [diffbot/controller_spawner-5] process has finished cleanly log file: /home/rod/.ros/log/3809b1b8-7579-11eb-99a1-f17e41f2f6b1/diffbot-controller_spawner-5.log

Russ76 commented 3 years ago

My Rosserial library doesn't seem to contain the diffbot_msgs package. How does it get there? Before, I just manually copied your Encoder.h file from a catkin build directory, or some such.

fjp commented 3 years ago

Hi Russ, good progress!

Maybe the Arduino IDE works on the Raspi?

Yes, I also flashed the Teensy using the Raspi which is running Ubuntu Mate 20.04 and ROS noetic. But most often I flash with my laptop, also running Ubuntu 20.04 and ROS Noetic.

Running roslaunch diffbot_control diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/corridor.world' should open up the gazebo simulation and RViz without problems. In your case it looks like some missing system dependencies. It seems some ros control or gazebo ros control packages are missing. This is also something that needs to be improved. Inside your catkin workspace, could you please let me know what the output of this command is: rosdep check diffbot_control?

My Rosserial library doesn't seem to contain the diffbot_msgs package. How does it get there? Before, I just manually copied your Encoder.h file from a catkin build directory, or some such.

To get the diffbot_msgs package inside the rosserial library you should to follow the steps outlined previously:

  1. rosrun rosserial_client make_libraries ~/Arduino/tmp/
  2. Copy the diffbot_msgs folder (which includes the Encoder.h message definition) from the ~/Arduino/tmp/ros_lib/ folder into your ~/Arduino/libraries/Rosserial_Arduino_Library/src/ folder.

After that it should be possible to compile the encoder.ino.

Russ76 commented 3 years ago

rod@rod-raspi:~/catkin_ws$ rosdep check diffbot_control All system dependencies have been satisfied

Yes, I did get it to compile correctly!

Russ76 commented 3 years ago

The Teensy is able to control motors and send encoder info to Raspi now. Ticks and angle are changing rapidly. Thanks!

fjp commented 3 years ago

Nice, great that you got the encoder script working! You're welcome, and thanks for going through the not so finished documentation. This helps me to make it better.

rod@rod-raspi:~/catkin_ws$ rosdep check diffbot_control All system dependencies have been satisfied

In this case, I assume there is either another package missing or some performance issues because of this warning:

[WARN] [1614044942.865821, 0.000000]: Controller Spawner couldn't find the expected controller_manager ROS interface. [diffbot/controller_spawner-5] process has finished cleanly

On which hardware are you launching the command: roslaunch diffbot_control diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/corridor.world'? I tested this so far only on my laptop with a nvidia graphics card. So no virtual machine and I am not sure if it would run on the Raspberry Pi or Jetson board.

By the way thank you for the sponsoring :-)

Russ76 commented 3 years ago

That was on the Raspberry Pi that I ran the command. The second time it came up faster, but still with the error. Yes, my laptop is an I5 and should handle it better. I will try the command on that. It also has an Nvidia graphics subsystem.

Russ76 commented 3 years ago

Clicking on "Raspberry Pi Setup" on Diffbot website goes to "ROS Network Setup," not the correct page.

fjp commented 3 years ago

That was on the Raspberry Pi that I ran the command. The second time it came up faster, but still with the error.

Ok, then I guess the problem comes form the rather low performance of the Raspberry Pi.

Yes, my laptop is an I5 and should handle it better. I will try the command on that. It also has an Nvidia graphics subsystem.

Great, the simulation should work without problems on your laptop.

Clicking on "Raspberry Pi Setup" on Diffbot website goes to "ROS Network Setup," not the correct page.

Thanks for reporting this, I will keep track of this in #25.

Russ76 commented 3 years ago

Franz, if you want to see my tank robot, it's here. https://github.com/Russ76/Diffbot_results Also a couple attempted runs, not quite performing yet, log info in that repo.

fjp commented 3 years ago

Hi Russ, your tank looks good!

I also went through the the logs and here is what I can suggest for now:

 * /diffbot/mobile_base_controller/wheel_radius: 0.0325
 * /diffbot/mobile_base_controller/wheel_separation: 0.15

These values seem to be the same that I am using for DiffBots small wheels. I am not sure how to best set the parameters for the wheel tracks your robot has. Also check that the wheel separation is correct. You can change them in the diffbot_control config.

I also suggest you check with what rate your hardware interface runs. I had that set to 50Hz previously but I encountered some problems when this was too high. So I went back to 10Hz. This can be done in the diffbot_base_.cpp.

[ INFO] [1615070999.791095327]: pid namespace: pid/left_motor
[ INFO] [1615070999.792300345]: Initialize PID
[ INFO] [1615070999.793489015]: Initializing dynamic reconfigure in namespace /diffbot/pid/left_motor
[ INFO] [1615070999.887357827]: Update PID Gains: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-6.15385, out_max=6.15385
[ INFO] [1615070999.914458657]: Initialized dynamic reconfigure
[ INFO] [1615070999.914861756]: Initialized PID: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-6.15385, out_max=6.15385
[ INFO] [1615070999.915077534]: Update PID output limits: lower=6.15385, upper=-6.15385
[ INFO] [1615070999.915260114]: pid namespace: pid/right_motor
[ INFO] [1615070999.915427827]: Initialize PID
[ INFO] [1615070999.915547880]: Initializing dynamic reconfigure in namespace /diffbot/pid/right_motor
[ INFO] [1615070999.995873276]: Update PID Gains: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-6.15385, out_max=6.15385
[ INFO] [1615071000.023189355]: Initialized dynamic reconfigure
[ INFO] [1615071000.024331051]: Initialized PID: F=0.8, P=0.35, I=0.5, D=0.01, out_min=-6.15385, out_max=6.15385
[ INFO] [1615071000.025448900]: Update PID output limits: lower=6.15385, upper=-6.15385

The above shows the initialization of the PIDs that are running in the high level hardware interface for each motor. Form this, I see you have the same values that I use for my cheap motors. I suggest you try without PID first. For example set the F=0.0, P=1.0, I=0.0, D=0.01. The inital values should be set here in the diffbot_hw_interface.cpp. And you can change the values during runtime with the dynamic reconfigure rqt plugin.

Another error that might cause problems later on is the lidar:

YDLidar SDK initializing
YDLidar SDK has been initialized
[YDLIDAR]:SDK Version: 1.0.3
[CYdLidar] Error, cannot bind to the specified serial port[/dev/ydlidar] and baudrate[230400]
[CYdLidar::initialize] Error initializing YDLIDAR check Comms.
[ERROR] [1615070999.735053792]: Unknown error

Was it possible to run this without erros on its own?

Russ76 commented 3 years ago

Franz, thanks for the comments! I will get to work more on it Monday and Tuesday, which is my "weekend." Yes, I never saw the laser spinning, and I don't know why. At first I didn't have the optical sensors plugged into the USB3.0 ports but they are now. I don't have the Intel depth camera enabled yet, though the software is installed and I have seen the output on the Realsense viewer. Did you mean to have so much encoder output to screen? That seems to cover up other info and may take bandwidth.

fjp commented 3 years ago

Franz, thanks for the comments! I will get to work more on it Monday and Tuesday, which is my "weekend."

You're welcome, you are on the right track and I guess your tank will be running smoothly.

Yes, I never saw the laser spinning, and I don't know why. At first I didn't have the optical sensors plugged into the USB3.0 ports but they are now. I don't have the Intel depth camera enabled yet, though the software is installed and I have seen the output on the Realsense viewer.

Have you added your (non root) user to the dialout group? It could be a permission problem. I have described how to do this in the hardware interface/usb-devices section of the documentation.

But I am not sure if my advice works for the YDLidar, but the steps they describe here: https://github.com/YDLIDAR/ydlidar_ros/blob/master/docs/ydlidar.md seem to be promising.

Did you mean to have so much encoder output to screen? That seems to cover up other info and may take bandwidth.

I did use ROS_INFO_THROTTLE(1, "..."); previously but for my videos about the PID tuning I didn't want to throttle the logging. I agree I should, change this back to throttled logging. For now, you can just comment the logging or use a throttled version of it in the hardware_interface::read and hardware_interface::write methods and re compile.

One thing I forgot to mention previously: Because you have a tracked robot, I think the skid steer config of the ROS control diff_drive_controller might lead to better results in your case. I use the complete description for just two wheels. However, you should stilll be able to go with most of the hardware_interface cpp code, although I think you have to add two more wheel joints in the code (here in the diffbot_hw_interface.h, diffbot_control/config/diffbot_control.yaml and maybe even in the hardare_interface.cpp.

But it may also work with some modified settings in the current two wheeled version of the diffbot_controller/config. I would try with that first.

Russ76 commented 3 years ago

Yes, turning, especially on carpet, will take more power. The Lidar is now working. It needed more power! So installed a second pack of 3 three 18650s and a small regulator, and plugged that into the second Lidar jack. This will also be good when I power up the camera on the same USB bus. 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? Here are the topics: rod@raspi:~$ rostopic list /diagnostics /diffbot/encoder_ticks /diffbot/joint_states /diffbot/mobile_base_controller/cmd_vel /diffbot/mobile_base_controller/odom /diffbot/mobile_base_controller/parameter_descriptions /diffbot/mobile_base_controller/parameter_updates /diffbot/motor_left /diffbot/motor_right /diffbot/pid/left_motor/parameter_descriptions /diffbot/pid/left_motor/parameter_updates /diffbot/pid/right_motor/parameter_descriptions /diffbot/pid/right_motor/parameter_updates /diffbot/reset /diffbot/scan /rosout /rosout_agg /tf /tf_static Speaking of navigation, I wonder if the launch file is correct near the bottom of your "read me" when it says, "To map a new environment using slam gmapping..." , but the launch file includes Gazebo! Thanks!

Russ76 commented 3 years ago

Attempted to run diffbot_navigation diffbot_hw.launch

But it has errors and then a fatal error. This is to be run on real robot, no? I thought maybe this would complete commands for navigation. Here is output from that terminal. (I made changes to other programs as you suggested.)

rod@raspi:~$ roslaunch diffbot_navigation diffbot_hw.launch ... logging to /home/rod/.ros/log/4b11044c-811c-11eb-a83c-1f1384bec961/roslaunch-raspi-1606.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://raspi:44639/

SUMMARY

PARAMETERS

NODES / amcl (amcl/amcl) map_server (map_server/map_server) move_base (move_base/move_base) rviz (rviz/rviz)

ROS_MASTER_URI=http://192.168.1.179:11311/

process[map_server-1]: started with pid [1620] process[amcl-2]: started with pid [1621] process[move_base-3]: started with pid [1622] process[rviz-4]: started with pid [1632] qt.qpa.xcb: could not connect to display qt.qpa.plugin: Could not load the Qt platform plugin "xcb" in "" even though it was found. This application failed to start because no Qt platform plugin could be initialized. Reinstalling the application may fix this problem.

Available platform plugins are: eglfs, linuxfb, minimal, minimalegl, offscreen, vnc, xcb.

[ WARN] [1615324533.563991362]: global_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided [ WARN] [1615324533.581839764]: global_costmap: Pre-Hydro parameter "map_type" unused since "plugins" is provided [ INFO] [1615324533.590345652]: global_costmap: Using plugin "static_layer" [ INFO] [1615324533.662982558]: Requesting the map... [ INFO] [1615324533.886563634]: Resizing costmap to 384 X 384 at 0.050000 m/pix [ INFO] [1615324533.985963172]: Received a 384 X 384 map at 0.050000 m/pix [ INFO] [1615324534.021937220]: global_costmap: Using plugin "obstacle_layer" [ INFO] [1615324534.078273362]: Subscribed to Topics: scan [ INFO] [1615324534.231604715]: global_costmap: Using plugin "inflation_layer" ================================================================================REQUIRED process [rviz-4] has died! process has died [pid 1632, exit code -6, cmd /opt/ros/noetic/lib/rviz/rviz -d /home/rod/ros_ws/src/diffbot/diffbot_navigation/rviz/diffbot_navigation.rviz name:=rviz log:=/home/rod/.ros/log/4b11044c-811c-11eb-a83c-1f1384bec961/rviz-4.log]. log file: /home/rod/.ros/log/4b11044c-811c-11eb-a83c-1f1384bec961/rviz-4*.log Initiating shutdown!

[rviz-4] killing on exit [move_base-3] killing on exit [amcl-2] killing on exit [map_server-1] killing on exit shutting down processing monitor... ... shutting down processing monitor complete done

fjp commented 3 years ago

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.

Thanks for reporting, I'll add a new ticket to track this.

Speaking of navigation, I wonder if the launch file is correct near the bottom of your "read me" when it says, "To map a new environment using slam gmapping..." , but the launch file includes Gazebo!

I should update the Readme here for the real robot. The instruction in the readme are just for the gazebo simulation:

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

For the real robot I made a video where you can see the commands that I used:

image.

The commands I use in the video are (as you did correctly):

roslaunch diffbot_bringup diffbot_bringup_with_laser.launch

and in a new terminal on your remote/work pc (not the raspi) 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 robot_steering_rqt plugin.


Attempted to run diffbot_navigation diffbot_hw.launch This is to be run on real robot, no?

Sorry this is missing in the video, but the launch file should work to navigate the real robot using this diffbot_hw.lauch in the diffbot_navigation package. After you have created and saved a map (with the map_server map_saver command), you should be able to run the launch file on your work/remote pc (not the raspi), as this will launch RViz, which seems to crash in your case:

REQUIRED process [rviz-4] has died!

Russ76 commented 3 years ago

Franz, Thanks for more guidance! You may be interested in this repo that I worked with a couple years ago, and would still like to get working: https://github.com/norlab-ulaval/husky-trainer I suspect that it requires a good 3D lidar scanner. I couldn't get it to work with Zed and "depth_cloud to laser_scan" node. This "teach and repeat" capability would be sweet to own. By the way, that's a sharp video you made!

Russ76 commented 3 years ago

The tank is running as it's supposed to! Laser map comes up fast. I had to add steering plugin to diffbot_slam.launch in order to control it. Otherwise it sat and spinned in place! Also got the Gazebo sim working on laptop yesterday. So making real progress! Hope all is well in Austria!

fjp commented 3 years ago

Hi Russ, you are welcome and glad you got the tank working 👍

The https://github.com/norlab-ulaval/husky-trainer looks interesting indeed, I hope to find more time soon to try it. But first I want to work on the other open TODOs/Issues.

I had to add steering plugin to diffbot_slam.launch in order to control it.

True, that's missing. But because it is also common to use other steering tools such as the http://wiki.ros.org/teleop_twist_keyboard I didn't add it explicitly in the launch file.

Hope all is well in Austria!

Thank you everyting is fine. I hope in Hastings too!

Russ76 commented 3 years ago

Here's an interesting top level framework: https://www.kth.se/profile/diogoa/page/a-ros-integration-framework-for-behavior-trees Later, Russ

Russ76 commented 3 years ago

Now I'm using an Xbox controller, wired, via laptop, to drive tank. She's quite hard to control. How can I remove the PID routine? My teleop_twist_joy publishes -0.5 to 0.5 ranges. Is that correct for the input to diffbot/mobile_base_controller/cmd_vel? I tried using the dynamic_reconfiguration tool but didn't have much luck there. It certainly does change how she responds!

fjp commented 3 years ago

Hi Russ, I haven't tested using a controller so far but it should work.

You can see and adjust the linear and angular controller velocity and acceleration limits in the diffbot_control.yaml. The PID also uses these values in the hardware_interface. Before disabling the (F)PID controller, I would start setting F (Feed Forward Gain), I (Integral) and D (Differential) all to zero and just the P (Proportional) to 1, here. Depending on what happens you might have to reduce the proportional gain, in case of instability (e.g. wheels turning back and forth). From there on, you can try to slightly increase the I and D values and check if it improves the result.

The calculated (F)PID output value is actually used in the hardware_interface::write method. Though you can try to write the calculated controller set command directly to the motors. This way you don't make use of the measured velocities from your encoders and don't take the actual error (measured velocity - commanded velocity) into account. So my advice is to at least use the proportional gain. I also had a hard time to tune the other values correctly and still think that it could be better. However, in the end a more sophisticated controller should be used to get better results, like discussed in #13.

If you really want to try disabling the PID, it should be possible when you set just F=1 (or a value near 1) and all other values to zero (P=0, I=0, D=0). This setting will directly use set_point velocity from the controller (diff_drive_controller in our case) and write it to the motors. So no need to change the source code.

Also please remember that ROS control assumes that the commands its controller generates, must be executed by the motors.

Russ76 commented 3 years ago

Franz, I tried these new values, 0,0,0,1 and wheels did jump back and forth. So I put them back as they were. Using pared down launch files, and tank on a stand, without touching the joystick at all, the motor_left value is -14, and that track is turning, not slowly. Why doesn't it send the zero value? I tried changing values in the control.yaml file but this didn't change the left motor running by itself. I checked hw_interface.cpp and it has 42 refs to left and 15 to right. Why are they not equal?

fjp commented 3 years ago

I can confirm a similar behavior. Let's keep track of this problem in #30. I'll try to find out why the initial read velocity isn't zero, because this seems to be the root cause for this issue.

I checked hw_interface.cpp and it has 42 refs to left and 15 to right. Why are they not equal?

This is just because I use std::left to format the log strings. For example here:

https://github.com/fjp/diffbot/blob/89de446dea5644077287c2c1133d5e3cea5c8984/diffbot_base/src/diffbot_hw_interface.cpp#L124-L128

fjp commented 3 years ago

Just wanted to give a short update on the initialization issue mentioned in #30. I think I found the problem and hope the uncontrolled wheel spin at the start is solved soon. For more details please see my latest comment.