Close
0%
0%

Build your own TurtleBot 3 backbone

Implement the fantastic robotic packages offered by the TurtleBot3 robot on a budget without sacrificing features and performances.

Public Chat
Similar projects worth following
Turtlebot3 is the perfect platform to deep into robotics and AI.
I propose you to build the TB3 backbone on a budget: replacing expensive Dynamixel servomotors and OpenCR board by cheaper components compatible with all ROS TurtleBot3 packages.

NB: this project was originally focused on replacing expensive hardware, but it now proposes to build a complete TurtleBot3 (actually called foxbot) robot with an embedded SBC based on Jetson Nano

Why this project ?

It makes no doubt that ROS (Robot Operating System) is the most common framework for robotics. It offers a powerful middleware for interconnecting sensors and actuators with already packaged drivers and state-of-the-art algorithms (SLAM, vision based algos, IA, control...) also already packaged by the huge open source community.

Among the countless robotics projects based on ROS, one of them shine by its number of features and its rich documentation and tutorials: the famous TurtleBot3. Its open source hardware with modular mechanics is the base for variety of robot's type: 2 Wheel-Drive, 4WD, 6WD, omnidirectional wheels, embedded robotic arm:

http://emanual.robotis.com/docs/en/platform/turtlebot3/features/#worlds-most-popular-ros-platform

NB: Although this project is oriented on turtlebot's like robot, those features could be used for any robotics platform of your mind

Current Architecture

Hardware components on the Waffle TB3 and Burger TB3 (2WD) are listed above:

  • Propulsion Motors: Dynamixel XM430 servomotor (expensive). Dynamixel servomotors are high quality and performance servomotors, offering advanced features like torque, rate and position control with a complete SDK. All hose features are not needed and came at a price.
  • Microcontroller running low level task: OpenCR board based on Cortex M7 (expensive). This board delivers power for all components, it integrates an IMU sensor, different communication and I/O ports
  • Single Board Computer (SBC) running high level task: RaspberryPi (affordable)
  • Sensors: LIDAR, cameras (affordable)

Goal

This project aims at replacing expensive hardware components with cheaper ones, while keeping software compatibility. Thus Dynamixel servos with OpenCR board will be respectively replaced by brushed DC motors with Arduino Due (based on Cortex M3). The microcontroller firmware will be adapted to match modified hardware.

In order to run high level tasks such as SLAM or vision based algorithms, the Rapsberry Pi is replaced by the Jetson Nano.

Features

In this section, I will update the developing state of features covered by Dynamixel+OpenCR converted into BrushedDC+Due.

  • Motor control: convert velocity commands received from SBC into wheel rates (kinematic model), estimate wheel rate with sensors, perform wheel rate control, distribute power to motors [DONE]
  • Odometry publishing: compute odometry from encoders used for localization [DONE]
  • IMU publishing: compute unbiased gyro rates and accelerations along with attitude used for localization (current TB3's implementation use biased values) [WIP]
  • Robot state publishing: several states indicating battery voltage level, hardware faults [TBD]

Those features constitute the core of the robot and could be seen as turtle's backbone.

Project organization

For this project, i decided to follow an iterative approach: build and develop from lower to higher components while trying to validate each performance individually. Some important points regarding this project:

  • this project focuses on TurtleBot3 "backbone" but came in parallel with the design of a complete "TurtleBot3 like" robot
  • each feature involves both hardware and software development that will be covered in logs
  • to facilitate hardware integration, electronics will be simple and based on existing boards (regulators, H bridges, IMU, current sensors...), even if ideally a complete PCB should be designed
  • to validate features a complete platform will be design, based on TB3 base plates proposed by Robotis to reduce mechanical design work

step - 2.61 MB - 09/08/2019 at 21:23

Download

step - 73.55 kB - 09/08/2019 at 21:23

Download

  • [NEWS] Jetson Nano and Arduino Code

    matop12/21/2019 at 09:29 2 comments

    Here are some news of the project, for now IMU calibration is paused, I have been mainly working to set ROS on the SBC.

    SBC

    The one I chose is the popular Jetson Nano from Nvidia, which offers a powerful CPU/GPU in a small form factor. It doesn't include WIFI chip by default, so you need to choose one, mine is something like TPLink WN822N, I am totally not able to know if it's a choice or not. The Jetson is mounted on the upper plate.

    Jetson Nano comes with a specific OS based on Ubuntu 18.04, it includes precompiled libraries using the onboard GPU. I installed ROS on it and set the rosserial communication with the Arduino Due.

    LIDAR


    The LIDAR  is the LDS01, it is the same that the original TurtleBot3. It is mounted centered on top of the upper plate with a specially designed 3D part (available in project resources). In comparison with the RPLIDAR A2, it seems to have a lower range.



    Arduino Code

    The Arduino core script running on DUE is now available on github. For now it includes:

    • velocity commands subscriber
    • kinematic that transform velocity in body frame to wheel rate
    • rate controller based on PID (described in previous log)
    • odometry publisher

    Some extra libraries are still needed to compile the code and will be added soon.

  • IMU processing (part 2)

    matop11/03/2019 at 17:45 0 comments

    Introduction

    As detailed in IMU Processing - part 1, the calibration method for accelerometers was not sufficient to guarantee a good precision. Indeed error reached up to 0.15g error on some axis, that corresponds to 8.5deg.

    Spherical model calibration

    The goal of the calibration is to shape a sphere from a distorted one namely the uncalibrated measures of the accelerometer when rotated around its 3 axes.

    As we look to shape a sphere, we need the maths detailed in this paper: https://jekel.me/2015/Least-Squares-Sphere-Fit/. Because we are not confident with only a few measures (that correspond to the number of unknown parameters to calibrate), we need to surdetermined our system with a lot of measures using Least Square.

    They are several ways to solve it:

    - Singular Value Decomposition: described here that compute the pseudo inverse matrix formed by our surdetermined system that then give the unknown parameters. This method is 'lighter' enough to run on microcontroller, and gives good results

    - Optimization Solver: minimize the criterion defined by the raw points to match the sphere model by varying sphere equation parameter. There are many ways to solve optimization problem, and the only ones I found that are well documented require a lot of integration to run on micro controller.

    Advanced model calibration

    After digging the web, I finally landed on a more advanced error model for MEMS sensors. This model also takes into account axis misalignment and axis non orthogonality, more info on the paper. Luckily the method has been implemented as well, more detail on the next paragraph.

    Integration approach

    Finally i decided to not perform the sensor calibration onboard, instead raw values will be processed on a computer running solvers. The obtained results will be then used by the microcontroller (Arduino Due in my case).

    The calibration workflow is currently not frozen, but here are some ideas:

    • get the calibration results and directly compile the code (the simplest one, and currently used)
    • try to fetch a results file located on SBC at ROS node startup (unsure how it is possible from the ucontroller)
    • dynamically send raw data and fetch results on demand through a ROS service for example (way more longer to implement)

    As told before an excellent integration work of the selected method as been done by albertopretto on this github repo. It relies on the Ceres solver, the Google open source solver (used in SLAM cartographer). The implementation only cover gyro and accelero, I decided to use the sphere model to calibrate magnetometer and solve the least square problem with Ceres.

  • Mechanical design (part 2)

    matop09/21/2019 at 21:41 0 comments

    First Layer

    Switches holder

    I use two switches, one to power the SBC and another one to power motor. They come with they respective LED that indicates which device is on.

    The plate that hold them also serves as spacer to support the upper plate. A symmetrical plate without switches  and narrower to allow battery passage completes the structure.

    Electronic boards holder

    Electronic boards are kept slightly elevated from the first layer thanks to a 3D printed 'table'. This part allows cables to pass under and reduces the 'messy aspect' near switches and battery.

    Double sided tape is used to maintain boards. You can find the CJM CU 758 current sensor and the 5V pololu regulator.

    Others

    Basics 'bornier' are used to dispatch power.

    IMU holder is fixed at the current center of rotation of the platform: namely the middle of the 'motor line', it may be defined as the center of the platform in the future.

    Second layer

    As the project slowly drifts into building a complete robot platform which is needed to test and validate TB3 packages, I present you parts related to 'higher level' components, located on the upper plate.

    Lidar mount


    In order to elevate LIDAR from the upper plate, I use an intermediate wooden plate (but could be 3D printed) on which a specific part as been design to match shapes of the LDS01 LIDAR. To gain height, nylon spacers and a adaptation part are used.


  • Mechanical design (part 1)

    matop08/27/2019 at 21:56 0 comments

    Overall structure

    Building a complete robotic frame is an interesting challenge but could be really time consuming. In order to focus on project's goals, I decided to use TurtleBot3 plates which present many advantages: numerous holes offer good modularity and molded plastic used present a higher stiffness than most 3D printer materials.

    Motor holder

    Motor holder are composed of two parts that tighten motor with 4 screws like a vises. Motors are soft mounted to prevent vibrations that cause noise.

    IMU holder

    This cube will be used for algorithm tuning and calibration methods development, some holes with M2.5 inserts allow to fix it on the TB3 plates. As explain in a previous log, IMU is soft mounted with "thick tape".

    Here is also an overview of the Arduino Due with its proto board.

    Caster ball

    Not really a ball, but should do the job.

  • IMU processing (part 1)

    matop08/12/2019 at 17:38 2 comments

    Hardware integration

    IMU used for this project is the MiniIMU-v2 from Pololu, it incorporates several chips that offers 9 degrees of freedom, allowing a complete attitude estimation.

    • magnetometers, LSM303, 30Hz Output Data Rate, 1.3gauss scale
    • accelerometers, LSM303, 50Hz Output Data Rate, 8g scale
    • gyrometers, L3G, 190Hz Output Data Rate, 25Hz cutoff frequency, 2000°/s scale

    In order to passively filter noise from mechanical structure especially from motors, the IMU should be soft mounted. It is also possible to use integrated filters provided by the chip, all information regarding available filtering frequency and settings are available in the datasheets.

    Attitude algorithm

    The algorithm used on the OpenCR firmware is the Madgwick complementary filter. This filter produces good results regarding advanced sensor fusion algorithms (like Kalman filters), and is able to produce complete orientation (yaw, pitch and roll), when using magnetometer (it is not the case on the current OpenCR firmware).

    I also use this algorithm for this projects with some improvements:

    • include magnetometer measurements
    • allow varying time processing
    • compute on-line gyrometers biases
    • sensors calibration

    Sensors calibration

    Gyrometer:

    An automatic bias computing is performed at firmware startup, no immobility check are done doing this process, so robot should absolutely be kept static during this period!

    Biases evolve in regard of temperature and mechanical stress on the board, although their computing during robot operation is not mandatory.

    Accelerometer:

    Madgwick filter uses accelerometer to compute gyroscopes biases. In details, each time acceleration norm equals to gravity (the robot's speed regarding terrestrial reference frame is constant), so if accelerometer have biases this condition never appends and gyroscope estimated rates diverge from real rates.

    The selected method is the 6-point tumble sensor calibration, which use a quite simple sensor model, with scale factor, cross-coupling and offsets. All details can be found on this document from STMicroelectronics.

    This calibration must be done after fixing the IMU on its support, because fixing it causes mechanical stress on the PCB which must be calibrated. Its not mandatory to realize systematically this calibration at startup, calibration data could be stored in memory.

    Magnetometer:

    The selected method consists in measuring scale factors and offsets which  correspond to hard iron distortions. More details and code are available at this really well made github page from kriswiner.

    This calibration must be done after fixing the IMU on its support and after inserting it inside the robot frame because all magnetic components such as metallic frame or other electronics components could modify the sensor behavior (hard iron). As for magnetometers, this calibration could be done not systematically.

    Development and results

    Magnetometer calibration could be easily implemented as explained in kriswiner's document.

    The rotation process requires to rotate IMU around its three axis, for now result is given through the arduino console and needs further development to be integrated with ROS (it might already exist package to calibrate IMU that could be used).

    After realizing several calibrations on the same magneto, converging results tend to indicated that process is OK.

    Accelerometer calibration using 6 points calibrations method doesn't offer such good results. 

    First the method requires least square regression to obtain calibration matrix coefficients, altough this problem may have been already tackle with embedded software constrains, it still represent significant development effort.

    Second,  this algo relies on the strong assumption that each measured point correspond to an axis oriented strictly colinear to gravity (ie equal to -g or g). Altgough a speficic cubic part has been designed, the mechanical tolerance can't guarantee that assumption....

    Read more »

  • Motor speed control

    matop08/11/2019 at 19:54 0 comments

    Wheel speed estimation

    Each hall encoder produces nb_{rising edges} logical rising edges per motor rotation (due to multiple magnetization points on encoder ring).

    Speed estimation relies on counting the number of logical rising edges nb_{encoder ticks} during an known time interval dt for a single sensor.

    Wheel speed is then estimate with the following relation

    At low speed, the signal is noisy and filtering is applied. The filter consists in a running average with higher weight on the last value. Some tuning on filter size and weights might be needed.

    Wheel direction estimation

    In order to estimate direction, during each rising edges of sensor A, the logical state of sensor B is read. Then a logical state is associated with a direction.

    This method is quite robust but sometimes presents glitches which are removed using a median filter.

    Control strategy

    Linear and angular reference velocity in the robot frame are converted into left and right wheel reference speed using differential drive kinematics model.

    http://www.cs.columbia.edu/~allen/F17/NOTES/icckinematics.pdf

    Then a PID controller tends to make estimate speed converge to reference speed for each motor. PID's output is not directly PWM value but PWM rate.

    Controller tuning

    Tuning controllers could be painful and require basic understanding on effects of each Proportional, Integral and Derivative terms. To accurately tune your controller you will need to log several debug variables while playing a step reference input.

    The ROS package called plotjuggler offers a complete UI for real-time visualization and logging of topics values. Simply publish debug topics with interesting values.

    1. Set I=0 and D=0, progressively increase P until motor get a response with a "important" overshoot (more than 50% of a step respons. Debug variables: reference speed, estimated speed, PWM rate, PWM value
    2. Motor response time could be long, to reduce this increase progressively D value. Be aware that this term tends to amplify noise. Debug variables: reference speed, estimated speed, PWM rate, PWM value, PWM rate from Derivative term
    3. At this point, PWM value might vary a lot, try to smooth it by adding Integral term

    Results

    Plotting reference angular rate in blue and estimated angular rate for both motors give the following performances:

    • settling time 95% = 350ms
    • static error = 0

    Control and estimation loop frequency

    This section presents some 'business rules' that will help you to tune your controller loop and filters.

    The controller frequency should be at least twice higher than your robot dynamics bandwidth (less than 5Hz for turtlebot-like robot), so running that loop at 50Hz should be able to produce a good stability and rapidity control.

    The speed wheel estimation frequency should not exceed twice the minimal desired speed. From the equation given at Wheel speed estimation, it is possible to calculate the corresponding frequency.

    About filter: note that delay is your worst enemy, it reduces rapidity and stability. So the more you filter raw encoders value, the more you add delay into control.

  • Hardware selection

    matop08/11/2019 at 16:45 0 comments

    Specification

    • expected linear speed for a 40mm wheeled robot -> [10mm/s; 1m/s]
    • transformed into wheel rotational speed -> [XXRPM; XXRPM]

    To match spec, we need to paid attention motor's type. For our application, three type of motor would have been OK to replace Dynamixel servo: stepper motor, brushless motor or DC geared motor. Similarly, several angular position sensors would have fit our needs:

    • Quadrature Hall Sensors, they produce analog signal proportional to magnetic field
    • 1 or more Logical Hall Sensors (at least 2 are needed to estimate direction). They produce a logical high state when sensors reach magnetic threshold corresponding to a locally magnetized area on the ring
    • Magnetic encoders
    • Optical encoders

    In order to keep costs as low as possible, widely available DC geared motors with 2 logical hall sensors are used for this project.

    Motor and Encoder sizing

    Characteristics

    • max speed: RPM
    • voltage: 6V
    • torque: largely enough
    • reduction gear: 1:850

    NB: the reduction factor must be quite important, because angular position resolution depends on this value, enabling low rate control.

    Motor piloting board

    To power motors the popular double H-bridge L298N board is selected. Documentation an tutorial for this board are widely available on the web.

    This board only support up to 2A per channel while our motors could demand up to XXA. In order to use safely this board, current needs to be monitored.

    Current sensing

    As detailed above, sensors will be used to monitor current and prevent overcharge on L298N. I choose the CJMCU-758 with ACS758LCB-050B-PFF-T that allows bidirectional current measurements.

View all 7 project logs

Enjoy this project?

Share

Discussions

JCWilliams1003 wrote 11/05/2022 at 17:57 point

Hi! Very impressive project, I am hoping to apply some portions of this project to an Arduino Nano. I believe I am having some issues with the buffer size of the Arduino and the serial rate. I was wondering if you could recommend a possible buffer size for communicating the information from the foxbot_core.io project with the raspberry pi? When attempting to communicate, I receive a notice that 80 bytes where expected but only 19 bytes were received. Thanks!

  Are you sure? yes | no

matop wrote 12/01/2022 at 10:30 point

hi, you could find the config used for this project here; but i only tried it on an Arduino Due: https://github.com/MattMgn/arduino-libraries/commit/7004090e31d7e86be491e0b547549c6407794342 

  Are you sure? yes | no

Bart wrote 09/17/2021 at 16:14 point

Hey there,

I'm Bart form Holland

My project a 4 wheel mecanum drive is now running on a Arduino Mega.  For 3 days was trying to build a sketch with odometry, similar to yours. But then ..on the mega.

After I ran into your project I ordered a Due, today I received it.

My compile was already done so it was a matter of uploading, i did not hooked all the motor wires encoders, i just wanted to test it and see if it running in sync with ROS.

I was afraid it would give me "the famous" unable to sync ... mismatch, version hydro error,  when running the serial_node.

... and it did.

But then.. 2 seconds later  it gave me the rest of the messages setting up subscriber to cmd_vel , publishing odom etc.

When rostopic list : it gives me all the topics /cmd_vel /diagnostics /odom etc.

When rostopic info : it gives  publisher : serial_node    perfect!! 

when publishing teleop_twist_mssg  - it works perfect again !!

But it still starts up with the

"the famous" unable to sync ... mismatch, version hydro error" 

When i'm running the turtlebot3_navigation.launch it RVIZ does not find a frame named odom (for startup).  To solve this i setup a TF_odom_broadcaster in your script. Now the odometry of the Due pops up in rviz when you what to select the Fixed Frame in de dropbox /odom...so that works.

Next week i will hook up the motors to see how it reacts. My plan is to make to 4 wheel compatible.

keep ya posted, thanks for sharing !!

Greets from Amsterdam

Bart

  Are you sure? yes | no

matop wrote 09/23/2021 at 11:29 point

Well done Bart!!

It's is very likely that a solution exists to run the code on a Mega as well. By tuning ArduinoHardware config for example: you could try to add the following line after importing the libs in foxbot_core_config.h (around the 37th line):

typedef NodeHandle_<ArduinoHardware, 15, 15, 512, 2048> NodeHandle;

it might also require to reduce loops frequency.

Thanks for the odom frame.

Send us some pictures of your setup!

Matt

  Are you sure? yes | no

Bart wrote 10/11/2021 at 18:34 point

thanks for the advise on the mega. For now i hope to finish this task with your code.

I posted the code on the first steps to make it 4 wheeled

https://github.com/BartVanderHaagen/Omni/blob/main/turtlebot_omni.ino

in the same repository the wheeltest, this one was just to test the cmd_vel and the moves, later i added the code to use the encoders.

https://github.com/BartVanderHaagen/Omni/blob/main/wheeltest.ino

this movie I recently posted

https://www.youtube.com/watch?v=-R-inA9GqPc

To use your code i need to calculate the force per (mecanum) wheel with some if statements. based on this theory

https://www.youtube.com/watch?v=Xrc0l4TDnyw&t=3s

I did not have much time to get in any deeper sofar. the debug_back_left end debug_back_right work but i did not try to use it yet.

I did some tests with the 2 wheels only but the base_link stays on its place (x, y) though it turns around z when rotating the wheels, so i think that's not good. 

You might have a look into the mecanum wheel code and help me get this job done for the due it would be very cool, to add this to the turtleproject...

Kind regards

Bart van der Haagen

  Are you sure? yes | no

matop wrote 10/13/2021 at 11:49 point

Bart,

For your omniwheel robot, you could simply use the equation (17) in this doc https://research.ijcaonline.org/volume113/number3/pxc3901586.pdf

It should work as your robot is a square, and you don't have to compute any forces (no dynamics here, only kinematics is required here).

You also need to use the cmd_vel.linear.y component which was 0 by design on a 2WD differential robot instead of only cmd_vel.linear.x and cmd_vel.angular.z.

  Are you sure? yes | no

Bart wrote 11/02/2021 at 19:01 point

The first steps are done, after studying the documents I still feel like there are different approaches when choosing a start angle or direction to call forwards, sideways backwards and so on... also changing the angle 90 degrees results in the next forward move to be sideways because it still gives feedback for a forward movement over the X-axis (for the map) for the robot the axis has changed 90 degrees.

In other words, as long as the robot is aligned forwards it is pretty precise.  

for now, when rotating 10 times around angular_Z (3.14) left it gives feedback of 32.30  also nice..

I still need the formula to subtract the angle for the next move. I found some video's on that i hope i can make that work.

overall I found that it would not be wise to only trust on the wheel odometry, its a really cool to fine-tune but the next steps are to use the IMU also and combine it with the laser odom. I also have the D435i depthcamera and saving up for the T.265 for the complete rtap_map functions. 

I really want to special thank you for sharing your great code. It helped a lot. 

If you like... 

Find me on LinkedIn in there is a ROS user group where I like to post videos on Omni (this one) and Flex my two-wheeled balance showcase.

Have a good one! 

 Bart van der Haagen

  Are you sure? yes | no

gssabu wrote 09/01/2021 at 10:50 point

Hello, I hope the covid situation got better where you live and you got to work more on this project.
My question is, how are you using the current sensor? I couldn't figure out how did you connect it to arduino nor I was able to find anything in the codes relating to the current sensor. Could it be just that you havn't got to that part yet?

I am really glad you decided to share all the info of the project. It has helped me greatly so far. So, thank you!

  Are you sure? yes | no

matop wrote 09/22/2021 at 09:33 point

Hi,

Unfortunately, the current sensor is not integrated yet on my robot. I have been recently working on a custom PCB with integrated L298, and planned to add the current sensor as well!

Some hints about using current sensor: it could be used for precise control (based on dynamics equations for example with motor and robot model) or to detect a blocked wheel.

Glad this project helped yours!

Matt

  Are you sure? yes | no

gssabu wrote 10/09/2021 at 07:08 point

Oh thats awesome. I find the size of the L298N module kind of inconvenient as well. So I was planning to use TB67H420FTG Instead since it seems like no changes to code would be needed. I liked DRV8835 more but I am not sure what changes I have to make to your code to get it to work. Coding is not really my strength sadly haha. 

  Are you sure? yes | no

gssabu wrote 01/22/2022 at 09:39 point

Hello, I was able to get further on this project following your guide, but I am now stuck on tuning PID controller. I couldn't figure out how to set up the P I D values in plotjuggler. In plotjuggler, under "streaming" i selected "ROS Topic Subscriber". Under "Timeseries List", I have "debug_left" and "Debug_right". But i can't figure out where i have to make the adjustments to PID values as mentioned in motor control part of your guide. If you don't mind, and only if you have spare time, would you be able to show how you have the plotjuggler set up?

Again thank you, I have learned so many things from this guide alone! 

  Are you sure? yes | no

Tor wrote 06/10/2021 at 13:56 point

Fantastic project. I'm building a turtlebot-like robot very similar to yours, but with a Pi 4 running Ubuntu Mate 20.04 and ROS Noetic, along with an Arduinio MEGA. My motors are, by complete chance almost the same as yours (i've linked to them at the bottom).

I'm using your arduino code for the firmware for the robot, but i'm having issues with the motors running VERY "jittery". I know that the problem lies somewhere in the arduino code, because i've run a simple motor_driver.ino firmware through a teleop node before without problem. I'm noticing that the current draw from the bench PSU is equally as jittery/jumpy as the wheels. It seems to stabilize a little bit as i turn up the linear velocity, but it maxes out at 0.22 m/s, and still acts jittery. Any clue as to what i can look into? I should say that i've had to change the rosserial buffer size from 512 to 1024 for the MEGA, otherwise it would drop the messages.

Thanks!

PS: check out the project if you're interested: https://www.instagram.com/torpanvilbot/

Motors: https://www.banggood.com/Machifit-25GA370-DC-6V-Micro-Gear-Reduction-Motor-with-Encoder-Speed-Dial-Reducer-p-1491039.html?rmmds=myorder&cur_warehouse=CN&ID=512742

Motor driver: https://www.banggood.com/DC-5-12V-30A-PWM-Dual-Channel-Motor-Control-Module-H-Bridge-Motor-Drive-Controller-Board-p-1255703.html?rmmds=myorder

  Are you sure? yes | no

matop wrote 06/23/2021 at 17:28 point

Hi, it seems that you need to tune the controller, I explain how to do it in this log: https://hackaday.io/project/167074/log/166955-motor-speed-control

Feel free to ask for more details

  Are you sure? yes | no

wildan wrote 03/17/2021 at 04:00 point

where we can get timer.h and medianfilter.h library ??

  Are you sure? yes | no

matop wrote 03/22/2021 at 19:40 point

Hi, you can get them in the arduino-librairies link in the description

  Are you sure? yes | no

wildan wrote 03/23/2021 at 02:14 point

Refer me to the link , I cannot find it in the description ?

  Are you sure? yes | no

Furhad wrote 03/08/2021 at 23:04 point

@matop  Just wanted to drop a thank you and share these videos from my project.

Navigation - https://www.youtube.com/watch?v=eKd1DAFYDSM

Gmapping - https://www.youtube.com/watch?v=IIkGoOUbjP0

  Are you sure? yes | no

matop wrote 03/15/2021 at 19:49 point

Nice, well done :)

  Are you sure? yes | no

Furhad wrote 02/15/2021 at 23:11 point

@matop Thank you for sharing this project. Could you please point me in the  right direction to help me understand how have you calculated RATE_CONV , RATE_CONTROLLER_MIN_PWM and RATE_CONTROLLER_MAX_PWM.

For RATE_CONV I am using this link - https://www.quantumdev.com/how-to-calculate-pulses-per-degree-for-an-incremental-encoder/

but i cannot seem to get the numbers you are getting for the motors you have used.

I am very new to this and I would appreciate the help.

  Are you sure? yes | no

matop wrote 02/16/2021 at 20:56 point

Hi Furhad,

For sure, you can get RAVE_CONV with : 

RATE_CONV = 2*pi/(Nb_increments_per_wheel_rotation) = 2*pi/853 (for my motor)

with Nb_increments_per_wheel_rotation = nb_increments_per_motor_rotation_per_encoder * nb_encoder_per_motor * nb_motor_rotation_per_wheel_rotation

nb_motor_rotation_per_wheel_rotation is generally given by the manufacturer as reduction gear ratio otherwise you need to measure it. 

RATE_CONTROLLER_MIN/MAX_PWM are saturations applied on the PWM, it is not mandatory and need to be tuned by hand.

Matt

  Are you sure? yes | no

Furhad wrote 02/16/2021 at 21:36 point

Thank you. @matop  I truly appreciate the help.

With your help I was able to get past the point where in Rviz when I was moving ahead there was an inclination towards the left . Now its so much better. Turns out because my Nb_increments_per_wheel_rotation was way off, 225 in my case or atleast I think based on Q&A section from where i bought my motors. The crappy motor I have did not come with a datasheet.

For me Next step would be to figure out how to calculate the actual value for nb_motor_rotation_per_wheel_rotation without the datasheets.

Again, Thank you very much!

  Are you sure? yes | no

matop wrote 02/23/2021 at 07:39 point

Well done @Furhad, An easy way to determine nb_motor_rotation_per_wheel_rotation is to write a simple Arduino code that increments a counter based on the encoder tics, then you rotate the wheel by hand for one complete revolution. The counter gives you what you were looking for.

  Are you sure? yes | no

Manu wrote 02/08/2021 at 22:30 point

Amazing Project, thanks!
I've build my own (a bit different, but mostly from your project).

Everything from the basic-operation section of the ROBOTIS e-manual is working and i also added a RPlidar A1M8 wich seems to work fine too.

Here comes my Problem, if i start the slam-node, i'am getting a error message on remote-pc:
[ WARN] [1612811758.641022463]: MessageFilter [target=odom ]: Dropped 100.00% of messages so far. Please turn the [ros.gmapping.message_filter] rosconsole logger to DEBUG for more information. 

If i debug it it's just saying: 
..Added message in frame base_scan at time 1612811914.542, count now 5
..Removed oldest message because buffer is full, count now 5..

So i just ignore it for now. But in rviz i'am getting a error: 
No transform from [wheel_left_link] & [wheel_right_link] to [odom]

Also if i'am debugging tf i can see there is no tf between odom and base_footprint.

maybe someone who build the project further on can help me here.

Thanks in advance

  Are you sure? yes | no

matop wrote 02/11/2021 at 21:56 point

You are welcome, glad to see new foxbots!

The problem comes from missing joint states pubishing in the foxbot project. It would be great to add this feature as well.

A good entry point would be to publish the JointState sensor_msgs for each wheel and updating their position and velocity (angular) with data from the hall sensors.

I could provide some support if needed :)

  Are you sure? yes | no

XSImnl wrote 02/17/2021 at 20:29 point

Thanks for the offer, but i got it working on my own (i think)..
..at least for a bit before i rostet my PCB and my Arduino.

I don't know right now if i go and order a new Arduino and repair my PCB or if i go with the original OpenCR and 2 XL430-W250.

 ..Whatever.
I forked the code on github and pushed my changes if somebody can make use of it. I'am for sure a rookie, the code isn't verified testet yet but at least it publishes a useful looking topic with data :D

  Are you sure? yes | no

matop wrote 02/23/2021 at 07:33 point

Nice @XSImnl, it would be great if you propose a pull request in order to merge it!

RIP to your board (and go for a new Arduino :D)

  Are you sure? yes | no

XSImnl wrote 03/03/2021 at 11:11 point

@matop sorry 4 the delay, pull is requested.

  Are you sure? yes | no

marcosjl31 wrote 12/12/2020 at 20:15 point

Hi !
I"ve finally completed the Bot (Raspberry pi 4 as SBC, ROS Noetic used). When I try to run the simple teleop example from doc, I get the message :

[INFO] [1607804025.824523]: Requesting topics...
[ERROR] [1607804040.832215]: Unable to sync with device;

I'm quite puzzled ! I run roscore on the PC (as per your instructables.com project).

If you could provide some hint where to search....

Thanx in advance


  Are you sure? yes | no

marcosjl31 wrote 12/12/2020 at 20:36 point

Ok. adding a Serial.begin(115200); before nh.getHardware()->setBaud(115200); in setup() function did the trick.
I do not get the 'unable to sync error messages' but it still doesn't work. How can i possibly debug ?

Thanx !

  Are you sure? yes | no

matop wrote 01/18/2021 at 19:00 point

You also need to make some modifications in your arduino ros_lib, I can't remember which settings need to be tuned, but you can check this commit: https://github.com/MattMgn/arduino-libraries/commit/7004090e31d7e86be491e0b547549c6407794342

Also some less powerfull Arduino boards were not able to handle the serial rate with the default control frequencies.

  Are you sure? yes | no

BenB wrote 08/01/2020 at 22:12 point

Cool project! I'm also modifying the Turtlebot3 ROS2 package to work on a different robot base: Parallax Arlo platform + Arduino Uno motor controller + Intel NUC for high-level compute. Have you figured out which files and functions to change on the TB3 package to work with a custom base?

  Are you sure? yes | no

matop wrote 08/30/2020 at 20:37 point

Thanks. You will need to adapt the code running on the Arduino, namely turtlebot3_core.ino.

If you go with the same low level HW (motor + encoder + motor controller) as described on this project and an Arduino Due, you will be able to run TB3 packages without problem.

  Are you sure? yes | no

BenB wrote 08/31/2020 at 04:09 point

I did something similar, rewriting turtlebot_node to map to my h/w. thanks

  Are you sure? yes | no

Darren wrote 07/23/2020 at 04:15 point

Can you provide the specs of the motors  or link

  Are you sure? yes | no

matop wrote 08/30/2020 at 20:45 point

I used cheap DC motor from aliexpress, around 8€/piece, an example here: https://www.aliexpress.com/item/33016407097.html

  Are you sure? yes | no

Steve wrote 08/30/2020 at 21:47 point

These look a lot like the motors running my rover "Tenacity":
https://hackaday.io/project/167736-tenacity-yet-another-sawppy-project

  Are you sure? yes | no

marcosjl31 wrote 04/28/2020 at 10:11 point

Hi
I've started to grab pieces to make this project. Something is really missing : an electronic schematic of the whole project could be a nice addition.
Thanx in advance

  Are you sure? yes | no

matop wrote 05/29/2020 at 12:37 point

I don't have a proper electronic schematic yet but you can find a drawing here:

https://www.instructables.com/id/Build-Your-Own-Turtblebot-Robot/

  Are you sure? yes | no

syahmi wrote 04/24/2020 at 17:13 point

It would be great if you can show me, which libraries that need to be added to upload the code. Because i had some problem with timer.

  Are you sure? yes | no

matop wrote 05/29/2020 at 12:35 point

you can find all needed libraries in the second github link in description

  Are you sure? yes | no

Peabody1929 wrote 08/16/2019 at 17:57 point

It would be great to see pictures of the assembly process.  They would help me build one.

  Are you sure? yes | no

matop wrote 08/20/2019 at 19:58 point

Thanks for your interest in this project, I planned to add pictures in a future log.

Don't hesitate to ask for more details

  Are you sure? yes | no

Similar Projects

Does this project spark your interest?

Become a member to follow this project and never miss any updates