πŸ€–
Robotics Handbook
HomeConnect
  • Welcome
    • Authors Note
  • Computer Aided Designs and Simulations
    • Computer Aided Design and Simulations
    • 3D Modelling CAD
      • SolidWorks
    • Simulations
    • PCB Design
  • ROS (Advanced)
    • ROS
    • ROS
      • Concepts and Packages
      • Manual and Quick Setup
    • Some Important packages
  • Hardware
    • Design Processes
      • Materials Selection
      • Build and Prototyping
      • 3D Printing and Machining
    • Fabrication Parts
  • Common Mechanisms
    • Wheels and Drives
    • Power Transmission
  • Career Paths & Research Opportunities
    • Career in Robotics
    • Job Roles In Robotics
    • Conferences and Journals
  • Companies Hiring for Robotics
  • Leading Institutes
  • Mathematical and Programming Foundations
    • Linear Algebra for Robotics
    • Calculus
  • Programming for Robotics
    • Common Languages
    • Algorithms
    • Digital Twin
  • Embedded Systems for Robotics
    • Embedded Systems
    • Microcontrollers
      • Microcontrollers (Advanced Theory)
      • Choosing a Microcontroller
    • Sensors and Actuators
      • Sensors for Robotics
      • Actuators for Robotics
    • Communication
      • Communication Protocols
    • RTOS
    • Power Systems
      • Battery Charging and Storage Best Practices
  • ML and Perception
    • ML and Perception
    • Reinforcement Learning
    • Cameras, Depth Sensors and LiDAR
    • Image Processing Basics (OpenCV)
    • Object Detection and Tracking
    • Example of a Vision Pipeline
  • Mobile Robotics
    • Mobile Robotics
    • SLAM and Navigation
    • Robot Kinematics and Dynamics
      • Some Kinematic Models
    • Trajectory Planning
    • AMR's and AGV's
    • MH633 : Mobile Robotics
      • Geometric Foundations
      • Kinematics
  • Frontiers and Emerging Fields
    • Frontiers and Emerging Fields
    • Humanoids
    • Autonomous Navigation
    • Bio-inspired and Soft Robotics
    • Space Robotics
    • Cobots
    • Edge Robotics
    • Medical Robotics
  • Drones, Rocketry and Aviation
    • Drones
      • Drone Anatomy
    • Rocketry
Powered by GitBook
On this page
  • Differential Drive Robots
  • Principle of Operation
  • Kinematics of Differential Drive Robots
  • Advantages of Differential Drive:
  • Disadvantages of Differential Drive:
  • Car-Like (Bicycle) Model Robots
  • Principle of Operation
  • Kinematics of Car-Like (Bicycle) Model
  • Advantages of Car-Like Model:
  • Disadvantages of Car-Like Model:
  1. Mobile Robotics
  2. Robot Kinematics and Dynamics

Some Kinematic Models

Differential Drive Robots

A differential wheeled robot is a mobile robot whose movement is based on two independently driven wheels placed on a common axis, one on each side of the robot body. This is a very common and simple drive mechanism for mobile robots.

Principle of Operation

The robot's motion is controlled by varying the relative speed and direction of its two drive wheels:

  • Straight Line Motion: If both wheels are driven in the same direction and at the same speed, the robot moves in a straight line (forwards or backwards).

  • Rotation in Place: If both wheels are driven at the same speed but in opposite directions, the robot will rotate about the central point of the axis connecting the wheels.

  • Curved Motion: If the wheels are driven at different speeds or in different directions (but not perfectly opposite at the same speed), the robot will follow a curved path. The robot rotates about a point known as the Instantaneous Center of Curvature (ICC) or Instantaneous Center of Rotation (ICR), which lies along the common axis of the two wheels. The distance to this ICC determines the radius of the curve.

Differential drive robots typically have one or more passive caster wheels for balance and support.

Kinematics of Differential Drive Robots

Let's define the parameters.

The radius of each drive wheel is denoted by r.

rrr The distance between the centers of the two drive wheels (the wheelbase or track width) is denoted by L. LLL The linear velocities of the left and right wheels along the ground, respectively, are denoted by V with subscripts L and R.

VLVRV_{L} \\ V_{R}VL​VR​ The angular velocities of the left and right wheels, respectively, are denoted by Ο‰ with subscripts L and R.

Ο‰LΟ‰R\omega_{L} \\ \omega_{R}Ο‰L​ωR​ Thus, the linear velocities of the wheels can be expressed in terms of their angular velocities and radius: VL=Ο‰Lβ‹…rVR=Ο‰Rβ‹…rV_{L} = \omega_{L} \cdot r \\ V_{R} = \omega_{R} \cdot rVL​=Ο‰L​⋅rVR​=Ο‰R​⋅r The linear velocity of the center point of the robot's axle is denoted by v.

vvv The angular velocity of the robot's body around the ICC is denoted by Ο‰.

ω\omegaω The position of the robot's center in a global coordinate frame is represented by x and y coordinates. (x,y)(x, y)(x,y) The orientation (heading angle) of the robot with respect to the global X-axis is denoted by θ. θ\thetaθ

Forward Kinematics Forward kinematics determines the robot's motion, specifically its linear velocity v and angular velocity Ο‰, and the change in its pose (Ξ”x, Ξ”y, Δθ) given the wheel velocities.

  1. Robot's Linear and Angular Velocity: The linear velocity v of the robot (midpoint of the axle) and its angular velocity Ο‰ are given by the following formulae: v=VR+VL2=r(Ο‰R+Ο‰L)2v = \frac{V_{R} + V_{L}}{2} = \frac{r(\omega_{R} + \omega_{L})}{2}v=2VR​+VL​​=2r(Ο‰R​+Ο‰L​)​ Ο‰=VRβˆ’VLL=r(Ο‰Rβˆ’Ο‰L)L\omega = \frac{V_{R} - V_{L}}{L} = \frac{r(\omega_{R} - \omega_{L})}{L}Ο‰=LVRβ€‹βˆ’VL​​=Lr(Ο‰Rβ€‹βˆ’Ο‰L​)​

  2. Instantaneous Center of Curvature (ICC): The signed distance R from the ICC to the midpoint of the wheels along the wheel axis is given by: R=L2VR+VLVRβˆ’VLR = \frac{L}{2} \frac{V_{R} + V_{L}}{V_{R} - V_{L}}R=2L​VRβ€‹βˆ’VL​VR​+VL​​ (Note: If the right wheel velocity equals the left wheel velocity, then the angular velocity Ο‰ is zero, the radius R is infinite, and the robot moves in a straight line. If the right wheel velocity is the negative of the left wheel velocity, then the linear velocity v is zero, the radius R is zero, and the robot spins in place.)

  3. Change in Pose (Odometry): Over a small time interval, denoted by Ξ΄t, \delta t the robot's pose (x, y, ΞΈ) changes as follows:

    • If the angular velocity Ο‰ is approximately zero (indicating the robot is moving straight): The change in the x-coordinate is Ξ”x. Ξ”xΞ”x=vβ‹…cos⁑(ΞΈ)β‹…Ξ΄t\Delta x \\ \Delta x = v \cdot \cos(\theta) \cdot \delta tΞ”xΞ”x=vβ‹…cos(ΞΈ)β‹…Ξ΄t The change in the y-coordinate is Ξ”y. Ξ”yΞ”y=vβ‹…sin⁑(ΞΈ)β‹…Ξ΄t\Delta y \\ \Delta y = v \cdot \sin(\theta) \cdot \delta tΞ”yΞ”y=vβ‹…sin(ΞΈ)β‹…Ξ΄t The change in orientation is Δθ. ΔθΔθ=0\Delta \theta \\ \Delta \theta = 0ΔθΔθ=0

    • If the angular velocity Ο‰ is not equal to zero (indicating the robot is turning): The new pose, denoted by (x', y', ΞΈ'), after the time interval Ξ΄t can be calculated. The coordinates of the ICC, (x with subscript ICC, y with subscript ICC), relative to the global frame are: xICCxICC=xβˆ’Rsin⁑(ΞΈ)yICCyICC=y+Rcos⁑(ΞΈ)x_{ICC}\\ x_{ICC} = x - R \sin(\theta)\\ y_{ICC}\\ y_{ICC} = y + R \cos(\theta)xICC​xICC​=xβˆ’Rsin(ΞΈ)yICC​yICC​=y+Rcos(ΞΈ) The new pose after the time interval Ξ΄t is then given by these formulae: xβ€²xβ€²=xβˆ’vΟ‰(sin⁑(ΞΈ)βˆ’sin⁑(ΞΈ+ωδt))yβ€²yβ€²=y+vΟ‰(cos⁑(ΞΈ)βˆ’cos⁑(ΞΈ+ωδt))ΞΈβ€²ΞΈβ€²=ΞΈ+ωδtx' \\ x' = x - \frac{v}{\omega}(\sin(\theta) - \sin(\theta + \omega \delta t)) \\ y'\\ y' = y + \frac{v}{\omega}(\cos(\theta) - \cos(\theta + \omega \delta t)) \\ \theta' \\ \theta' = \theta + \omega \delta t \\xβ€²xβ€²=xβˆ’Ο‰v​(sin(ΞΈ)βˆ’sin(ΞΈ+ωδt))yβ€²yβ€²=y+Ο‰v​(cos(ΞΈ)βˆ’cos(ΞΈ+ωδt))ΞΈβ€²ΞΈβ€²=ΞΈ+ωδt Alternatively, the instantaneous velocity components in the global frame are the time derivatives of x, y, and ΞΈ: xΛ™xΛ™=vcos⁑(ΞΈ)yΛ™yΛ™=vsin⁑(ΞΈ)dotΞΈΞΈΛ™=Ο‰\dot{x} \\ \dot{x} = v \cos(\theta) \\ \dot{y} \\ \dot{y} = v \sin(\theta) \\ dot{\theta} \\ \dot{\theta} = \omegaxΛ™xΛ™=vcos(ΞΈ)y˙​y˙​=vsin(ΞΈ)dotΞΈΞΈΛ™=Ο‰ These can be integrated over the time interval Ξ΄t to find the new pose.

Inverse Kinematics Inverse kinematics calculates the required individual wheel velocities (linear velocities V with subscripts L and R, or angular velocities Ο‰ with subscripts L and R) to achieve a desired robot linear velocity v and angular velocity Ο‰. The required wheel ground velocities are: VR=v+Ο‰L2VL=vβˆ’Ο‰L2V_{R} = v + \frac{\omega L}{2} \\ V_{L} = v - \frac{\omega L}{2}VR​=v+2Ο‰L​VL​=vβˆ’2Ο‰L​ And the required wheel angular velocities are: Ο‰R=VRr=1r(v+Ο‰L2)Ο‰L=VLr=1r(vβˆ’Ο‰L2)\omega_{R} = \frac{V_{R}}{r} = \frac{1}{r} \left(v + \frac{\omega L}{2}\right) \\ \omega_{L} = \frac{V_{L}}{r} = \frac{1}{r} \left(v - \frac{\omega L}{2}\right)Ο‰R​=rVR​​=r1​(v+2Ο‰L​)Ο‰L​=rVL​​=r1​(vβˆ’2Ο‰L​)

Advantages of Differential Drive:

  • Simplicity: Mechanically and conceptually simple.

  • Low Cost: Fewer parts compared to more complex steering systems.

  • Maneuverability: Can turn in place (zero turning radius), making it highly agile in constrained spaces.

  • Ease of Control: The motion is relatively easy to program and control.

Disadvantages of Differential Drive:

  • Slippage: The kinematic model assumes no wheel slippage, which is not always true in real-world scenarios, leading to odometry errors.

  • Sensitivity: Precise control of wheel speeds is necessary for accurate motion. Small differences in wheel speeds or diameters can cause deviation from a straight path.

  • Stability with Casters: Depending on the number and placement of caster wheels, stability can sometimes be an issue, especially at higher speeds or on uneven surfaces.


Car-Like (Bicycle) Model Robots

This model is kinematically equivalent to a bicycle, where typically the front wheel is steerable and one or both wheels can be driven. It's a common model for car-like robots.

Principle of Operation

The robot moves by driving its wheel(s) and changes direction by steering the front wheel. The no-slip condition implies that the wheels' velocity vectors are perpendicular to their axes. The robot rotates around an Instantaneous Center of Rotation (ICR) which is located at the intersection of lines perpendicular to the axes of all wheels.

Kinematics of Car-Like (Bicycle) Model

Let's define the parameters. The wheelbase (distance between the center of the front and rear wheels) is denoted by l.

lll The steering angle of the front wheel (angle between the robot's longitudinal axis and the direction of the front wheel) is denoted by Ο†. Ο•\phiΟ• The linear velocity of the robot (often taken at the center of the rear axle for a rear-wheel drive model) is denoted by v. Ο•\phiΟ• The orientation (heading angle) of the robot's body with respect to the global X-axis is denoted by ΞΈ. ΞΈ\thetaΞΈ

Forward Kinematics Given the robot's velocity v (e.g., at the rear axle) and steering angle Ο†, the robot's motion, specifically the rates of change of its global position and orientation (time derivatives of x, y, and ΞΈ), is described by these formulae: xΛ™=vcos⁑(ΞΈ)yΛ™=vsin⁑(ΞΈ)ΞΈΛ™=vltan⁑(Ο•)\dot{x} = v \cos(\theta) \\ \dot{y} = v \sin(\theta) \\ \dot{\theta} = \frac{v}{l} \tan(\phi)xΛ™=vcos(ΞΈ)y˙​=vsin(ΞΈ)ΞΈΛ™=lv​tan(Ο•)

Inverse Kinematics Given a desired body twist (commanded linear velocity v with subscript cmd, vcmdv_{cmd}vcmd​ and commanded angular velocity Ο‰ with subscript cmd), Ο‰cmd\omega_{cmd}Ο‰cmd​ we need to find the steering angle Ο† and the driving wheel's velocity (e.g., v with subscript rear for rear-wheel drive). The steering angle Ο† is often a direct command input or can be derived from the desired angular velocity. From the forward kinematics equation for the time derivative of ΞΈ, we have: tan⁑(Ο•)=Ο‰lv\tan(\phi) = \frac{\omega l}{v}tan(Ο•)=vΟ‰l​ So, the required steering angle is: Ο•=atan2⁑(Ο‰cmdl,vcmd)\phi = \operatorname{atan2}(\omega_{cmd} l, v_{cmd})Ο•=atan2(Ο‰cmd​l,vcmd​) (using the f(x)=xβˆ—e2piiΞΎxf(x) = x * e^{2 pi i \xi x}f(x)=xβˆ—e2piiΞΎx function for quadrant correctness, assuming v with subscript cmd is the robot's commanded forward speed at the reference point).

The velocity command for the driving wheel depends on which wheel is driven:

  • Rear-Wheel Drive: The velocity of the rear wheel, denoted as v with subscript rear, vrearv_{rear}vrear​ is the commanded linear velocity v with subscript cmd of the robot's reference point (rear axle). vrear=vcmdv_{rear} = v_{cmd}vrear​=vcmd​

  • Front-Wheel Drive: If the front wheel is driven, its velocity, denoted as v with subscript front, vfrontv_{front}vfront​ relates to the robot's reference point velocity v (at the rear axle) by the formula: v=vfrontcos⁑(Ο•)v = v_{front} \cos(\phi)v=vfront​cos(Ο•) So, the required front wheel velocity is: vfront=vcmdcos⁑(Ο•)v_{front} = \frac{v_{cmd}}{\cos(\phi)}vfront​=cos(Ο•)vcmd​​

Advantages of Car-Like Model:

  • Stability: Generally more stable at higher speeds than differential drive with casters.

  • Intuitive Control: Steering is similar to how humans drive cars.

Disadvantages of Car-Like Model:

  • Nonholonomic Constraints: Cannot move directly sideways. Has a minimum turning radius (unless it's a special design like four-wheel steering).

  • Complexity: Mechanically more complex than a simple differential drive due to the steering mechanism.

PreviousRobot Kinematics and DynamicsNextTrajectory Planning

Last updated 19 hours ago