Module 2 - Introduction to Mobile Robotics and Wheeled Robot Models
#Physics #Engineering #Robotics #Mobile_Robots #Control_Theory
Related:
Table of Contents:
A) Introduction to Module 2: Control of Mobile Robots (🎦 video 2.1)
Video: https://youtu.be/Cdm0WR5Mrwc
Welcome to Module 2 of the course on Control of Mobile Robots.
In Module 1, we discussed control theory as a general tool for managing systems.
In this module, we will focus specifically on mobile robots as the target application.
A.1) How Do We Drive a Robot From Point A to Point B?
Key Question: How Do We Drive a Robot From Point A to Point B?
Consider moving a robot from a point A to a point B.
Before answering how to achieve this, we must first identify what is needed:
-
Measuring the Goal’s Position and Turning it into Control Action:
- The robot must know where the target is.
- This information must then be transformed into a control action.
Note: *Designing the Controller: - We already have some foundational knowledge of controller design.
- The controller will translate goal information into actionable commands.
-
Understanding the Robot’s Sensors:
- To know about the environment and itself, the robot relies on sensors.
- We’ll explore sensor models, which:
- Abstractly represent how sensors gather information.
- Ensure the data is trustworthy for our controllers.
-
Modeling the Robot:
- To predict how the robot will behave under certain commands, we need robot models.
- To predict how the robot will behave under certain commands, we need robot models.
A.2) Goals of this Module (Differential Drive Robot)
For this module, we’ll focus on differential drive robot models and their dynamics.
We won’t dive into advanced perception.
Instead, we’ll use abstract sensor models that provide sufficient information for the task at hand.
A.3) Key Realizations About Robot Control (The World is Dynamic)
When designing controllers for robots navigating real-world environments, there are two crucial truths:
-
The World is Fundamentally Unknown:
- You can’t know the exact position of every obstacle (e.g., chairs in a building or trees in a forest).
- You can’t know the exact position of every obstacle (e.g., chairs in a building or trees in a forest).
-
The World is Dynamic:
- People move chairs, and wind makes trees sway. Therefore, static, pre-planned controllers often fail.
- People move chairs, and wind makes trees sway. Therefore, static, pre-planned controllers often fail.
A.3.1) Introduction to Behavior-Based Control (Divide and Conquer)
To address these challenges, roboticists divide tasks into smaller behaviors.
Each behavior represents a primitive control action tailored to specific situations.
Examples of Behaviors:
- Go-to-Goal: Drive to a specific waypoint or target.
- Avoid Obstacles: Avoid colliding with obstacles while moving.
- Follow Wall: Navigate by maintaining proximity to a wall (useful in structured environments).
- Track Moving Goals: Adapt to goals that move dynamically.
These behaviors can be combined to handle complex scenarios.
A.4) Behavior Demonstration Through Examples
A.4.1) Example1: Behavior vs. Planner-Based Approach
Planner-Based: When new information arises, the robot recalculates an entire plan, causing delays.
Behavior-Based: When new information (e.g., an obstacle) appears:
- The robot temporarily switches to an avoid-obstacle behavior.
- Once clear, it resumes its follow-plan behavior.
- Result: Behavior-based control is faster and more adaptive.
A.4.2) Example2: Dynamic Arc Behaviors
A Segway robot navigates using arc behaviors.
- Each behavior corresponds to a specific arc trajectory (varying sizes and shapes).
- The robot switches between these arc behaviors dynamically.
A.5) Motivation: Learning Goals for Module 2
By the end of this module, you will:
- Understand how to design individual behaviors (e.g., go-to-goal, avoid-obstacle).
- Learn how to combine behaviors effectively to create adaptive and robust robot controllers.
B) Differential Drive Robot Model and Unicycle Model (🎦 video 2.2)
Video: https://youtu.be/aE7RQNhwnPQ
B.1) The Differential Drive Robot Model
When designing controllers for robots, we need models to predict and influence how robots behave.
The first model we'll discuss is the Differential Drive Mobile Robot Model, one of the most common in robotics.
B.1.1) Wheels of a Differential Drive Robot
The following graphic represents the parts of a mobile robot that are important for the kinematic model.
A differential drive robot has:
- Two wheels that can spin independently at different velocities.
- An optional caster wheel for balance (usually at the back).
By controlling the velocities of the left wheel (
- If
, the robot moves straight forward. - If
, the robot turns left. - If
, the robot turns right.
B.1.2) Key Parameters: the Wheelbase and Wheel Radius
To model this robot, you need:
- Wheelbase (
): - The distance between the two wheels.
- Determines how tight the robot can turn.
- Wheel Radius (
): - The size of the wheels.
- Affects the relationship between wheel rotation and the robot's movement.
These parameters are straightforward to measure with tools like rulers.
B.1.3) What are we going to control in this model? (States and Inputs)
- Inputs:
: Velocity of the right wheel. : Velocity of the left wheel.
- States:
- Position (
): Where the robot is in the environment. - Orientation (
): The direction the robot is facing.
- Position (
B.1.4) Mathematical Model of a Differential Drive Robot (Forward Kinematics)
The differential drive kinematic equations map
These are represented as:
: Change in the robot’s -coordinate. : Change in the robot’s -coordinate. : Change in the robot’s orientation.
The equations are:
The linear velocities of the wheels are defined as:
Where:
: Radius of the wheel. : Angular velocity of the right wheel. : Angular velocity of the left wheel.
Here are the equations rewritten with linear velocities
Note: To learn how these equations are obtained, read Chapter 3 - Wheeled Kinematics (by Paul Furgale)
Forward Kinematics:
Differential Drive Model:
While the Forward Kinematics are very useful for implementation, this model is cumbersome for designing controllers.
To make controller design more intuitive, we will use a simpler model...
B.2) Making Control Design Intuitive: using the Unicycle Model
To make controller design more intuitive, we use the Unicycle Model, which focuses on the robot’s position and heading rather than wheel velocities.
B.2.1) Inputs for the Unicycle Model
- Translational Velocity (
): - How fast the robot is moving forward.
- Angular Velocity (
): - How quickly the robot is turning.
These inputs are easier to understand and control:
: "Move forward at this speed." : "Turn at this rate."
B.2.2) Unicycle Model Equations (Forward Kinematics)
The equations for the unicycle model are:
B.3) Connecting the Two Models
While the unicycle model is ideal for design, the robot’s actual hardware uses
To bridge this gap:
-
Derive relationships between
, and , :
-
Solve the system of equations for
and :
These equations let you map designed velocities (
We have a Model now. What’s Next?
Now that we have a model to translate high-level commands into hardware instructions, the next step is understanding the robot's environment:
- How does the robot perceive the world?
- What sensors does it use to gather information?
Stay tuned as we explore sensor models and how robots interact with their surroundings.
C) Odometry and Wheel Encoders in Differential Drive Robots (🎦 video 2.3)
Video: https://youtu.be/XbXhA4k7Ur8
C.1) Why Do We Need Odometry?
To control a robot effectively, we need to know its state, which includes:
- Position (
, ): Where the robot is. - Orientation (
): The direction the robot is facing.
Odometry provides a means to estimate the pose (position + orientation) of the robot by using sensors.
C.2) Types of Sensors for Odometry
- External Sensors:
- Measure external landmarks or signals.
- Examples:
- Ultrasound, Infrared, Cameras, Laser Scanners: Detect objects in the environment.
- GPS: Provides global position (useful outdoors but not indoors).
Example: LiDAR
- Internal Sensors:
- Located within the robot.
- Examples:
- Compass: Measures orientation.
- Accelerometers and Gyroscopes: Estimate position and orientation over time.
- Wheel Encoders: Measure the rotation of the wheels to estimate distance traveled.
Example: Wheel Encoder
Video: https://youtu.be/V1txmR8GXzE
Video:C.2.1) Example: using Wheel Encoders for Odometry
Wheel encoders are a common method for odometry in differential drive robots.
Step1) Calculate the Arc Lenght
They measure:
-
The distance traveled by each wheel:
- Left Wheel Distance (
): - Right Wheel Distance (
): represents the distance traveled by the center of the robot.
Note: Assumptions for Accuracy:
- Each wheel follows a constant arc.
- Velocities (and ) are constant over short time intervals. - Left Wheel Distance (
Based in the Unicycle Model, for the controller we only care about the center of the Robot,
In other words, we only care about the arc length
We can use the Arc Length Formula to calculate it,
We can define
Step2) Derive Odometry Equations
To update the robot’s pose (
over a very small time interval Δt, we use:
- Position Updates:
- assume
to be so small, that we can consider it as straight line,
- assume
We get this approximation,
- Orientation Update:
from our Kinematic model, we know that,
- Where
is the wheelbase (distance between the wheels).
We can define the velocities as follows,
then we substitute in the equation,
And finally, we write the orientation update as,
Summary:
C.2.2) How Do We Compute the Wheels Displacement using the Encoder?
How Do We Compute
-
Tick Counts:
- Each wheel encoder has
ticks per revolution (e.g., radians = ticks). - Encoders provide a total tick count.
- Each wheel encoder has
-
Change in Ticks in each Wheel in a small Time Interval:
- Distance Traveled by each Wheel:
- Where
is the radius of the wheel.
Note: we are assuming the wheels do not drift when rolling!
Using these formulas, we can compute
C.3) Challenges with Wheel Encoder Odometry (Drift!)
-
Drift:
- Small errors accumulate over time, leading to significant inaccuracies.
- Causes:
- Wheel slippage (e.g., spinning without touching the ground).
- Uneven surfaces.
- Example: A robot may become confused about its position due to accumulated drift.
-
Incomplete Information:
- Wheel encoders alone cannot account for all external factors (e.g., obstacles, inclines).
Takeaways:
- Wheel encoders are essential tools in robotics for estimating odometry.
- They are reliable over short distances but require additional sensors (e.g., cameras, GPS) for long-term accuracy.
- When using only encoders, always be mindful of drift and inaccuracies.
Next Steps
In upcoming modules, we will:
- Explore sensor fusion techniques to combine data from multiple sensors.
- Implement controllers that can adapt to the robot's perceived state.
D) Understanding Range Sensors and the Disc Abstraction (🎦 video 2.4)
Video: https://youtu.be/7_eJ_L-NYTg
D.1) Why Do Robots Need Environmental Information?
In addition to knowing their pose (
- Detect obstacles and other objects.
- Localize themselves within the world.
This is achieved using sensors, which we will abstract for simplicity.
D.2) Types of Sensors Used For Environmental Information
-
External Sensors:
- Gather information about the world.
- Examples:
- Range Sensors:
- Infrared, Ultrasonic, LIDAR (Laser Scanners): Measure distances to obstacles.
- Vision Sensors: Cameras that capture images or video.
- Tactile Sensors: Detect physical contact (e.g., bumpers).
- GPS: Provides global positioning (not suitable indoors).
- Range Sensors:
-
Internal Sensors:
- Provide data about the robot’s internal state.
- Examples:
- Wheel Encoders: Measure wheel rotation to estimate movement.
- Inertial Measurement Units (IMUs): Include accelerometers and gyroscopes for motion detection.
D.2.1) External Sensors: Range Sensor Skirt
What is a Sensor Skirt?
A range sensor skirt is a collection of range sensors arranged around the robot.
These sensors measure:
- Distance (
): To obstacles. - Direction (
): Relative to the robot's coordinate frame.
Examples of Range Sensors:
- Infrared Sensors: Detect proximity.
- Ultrasonic Sensors: Use sound waves to measure distance.
- LIDAR (Laser Scanners): Create precise maps of surroundings.
D.3) The Disc Abstraction (Simple Sensor Model)
Simplifying the Sensor Model
Instead of modeling individual sensors, we assume:
-
The robot has a circular detection area (a disc) around it.
-
Obstacles within the disc are detected with:
- Distance (
): To the obstacle. - Angle (
): Relative to the robot’s -axis.
- Distance (
Key Assumptions
-
The robot’s coordinate system is centered at its position (
). -
The angle
is measured relative to the robot’s heading ( ).
D.3.1) Example: Calculating Obstacle Positions
If the robot knows its pose (
Example: Global Obstacle Position
For an obstacle at a distance
D.3.2) Example: Applications of the Disc Abstraction (Rendezvous Problem)
Rendezvous Problem:
Robots must meet at a common location without communication.
Using the disc abstraction:
- Each robot:
- Detects neighbors within its disc.
- Computes the center of gravity (CoG) of neighbors.
- Moves toward the CoG.
- Result: Robots converge to the same point.
Behavior
- Robots adjust their position iteratively.
- Each step brings them closer to the rendezvous point.
D.4) Summary and Next Steps
**Summary:
-
Robot Models:
- Differential drive models.
- Unicycle models.
-
Odometry:
- Uses wheel encoders to estimate position.
-
Environmental Awareness:
- Sensors provide distance and direction to obstacles.
- The disc abstraction simplifies sensor modeling.
Next Steps:
Now that we have:
- A robot model.
- A method to estimate pose.
- An abstraction for environmental sensing.
We can begin designing controllers that use this information to navigate and interact with the environment effectively.
E) Behavior-Based Robotics (🎦 video 2.5)
Video: https://youtu.be/WRyVy576olM
E.1) Why Over-Planning Doesn't Work for Dynamic Worlds
- In dynamic and unknown environments:
- Over-planning becomes computationally expensive and ineffective.
- The world might not match assumptions, rendering the "optimal" plan useless.
Example: Industrial Robots vs. Exploratory Robots
-
Industrial Robots: Operate in controlled environments (e.g., welding the same spot 10,000 times daily). Over-planning is justified.
-
Exploratory Robots: Must adapt to unpredictable surroundings.
E.2) Behavior-Based Control: Designing Behaviors for Dynamic Environments
Instead of over-planning:
- Develop a library of useful behaviors, such as:
- Go to Goal: Drive towards a target.
- Avoid Obstacles: Reactively steer clear of obstacles.
- Other Behaviors: Follow walls, track moving objects, etc.
- Switch between behaviors dynamically based on the environment:
- Example: Detecting a power outlet when low on battery switches to a "Recharge" behavior.
E.3) Example: Designing a Behavior: Go to Goal
E.3.1) Robot Dynamics: Constant Speed Differential Drive Robot Model
Problem Setup
-
Robot Type: Differential Drive Robot.
-
Assumption: Constant velocity (
), only steering ( ) can be controlled. -
Goal: Steer the robot to align with the desired heading (
).
Constant Speed Differential Drive Robot Model
Note: Heading Dynamics: The robot's change in heading (
So, our Inputs are:
- Desired heading:
. - Current heading:
.
How can we control
Error Calculation: Define the error: $$ e = \phi_d - \phi $$
- This represents the difference between the desired heading and the robot's current heading.
- We could try to use a PID Controller, we have all that we need.
E.3.2) Control Design: PID Regulator
The angular velocity (
Where:
(Proportional Gain): - Reacts to the current error.
- Larger
means faster response but risks oscillations.
(Integral Gain): - Accumulates past errors to reduce steady-state error.
- Large
can also cause oscillations.
(Derivative Gain): - Reacts to the rate of change of error, improving responsiveness.
- Can amplify noise.
E.3.3) Caution: Handling Angle Wrapping (using atan2())
The Issue
- Angles are cyclical:
- Example:
radians, radians. , but radians. The actual error should be .
- Example:
- Large errors may cause instability or incorrect behavior.
The Solution
- Ensure
is always between and : - Use
atan2
(available in most programming languages like Python, C++, Java, etc.).
- Use
We are basically doing this,
but atan2(x,y)
makes sure that we do not loose information about the sign due to the division in atan(x)
. And its result is always between
Gráfica:
E.3.4) Conclusion: Behavior Go to Goal accomplished with a PID and atan2
The robot must steer to align with the direction of the goal.
-
Dynamics:
-
ensures the error is within .
-
-
Key Considerations:
- Use PID control for smooth alignment.
- Handle angles correctly with wrapping.
Video: https://youtu.be/4Y7zG48uHRo
E.4) Combining Behaviors (Go to Goal + Avoid Obstacles)
To navigate effectively, the robot needs multiple behaviors:
- Go to Goal: Drives toward a target location.
- Avoid Obstacles: Reacts dynamically to obstacles.
- Additional behaviors as needed.
Next Steps
- Develop controllers for individual behaviors.
- Test behaviors in simulated and real environments.
- Combine behaviors dynamically for robust navigation.
F) Designing the "Go to Goal" Behavior (🎦 video 2.6)
Video: https://youtu.be/Lgy92yXiyqQ
F.1) Overview: Combining Behaviors (Go to Goal + Avoid Obstacles)
To move a robot from Point A to Point B,
we need:
- A Go to Goal behavior to steer the robot toward the target.
- Possibly an Avoid Obstacle behavior for dynamic environments.
For a differential drive robot modeled as a unicycle:
- Velocity (
) is constant. - Control Input (
): Used to adjust the robot's heading.
F.2) Error and Controller Design
F.2.1) Recap: using atan2 to wrap the error
Error Definition
The error (
Handling Angles
Since atan2
function to wrap the error:
F.2.2) Calculate the Desired Heading based on the Goal
Desired Heading
The desired heading (
Then our controller would look something like this:
F.3) Example: Proportional Controller Implementation (Go-to-Goal)
Using a Proportional Controller:
Where:
: Proportional gain. : Error (wrapped using atan2
).
Implementation Steps
- Calculate
using the position of the robot and the goal. - Compute the error
. - Wrap
using the atan2
function. - Use the controller to compute
.
F.3.1) Attempts and Insights (Go to Goal)
Attempt 1: Forgetting Angle Wrapping
- Problem: Without wrapping
to , the robot becomes unstable. - Result: Erratic behavior when
or is outside the expected range.
Missing...
Attempt 2: Low Gain (
- Problem: The robot turns too slowly, leading to spiraling behavior.
- Observation: Higher speeds require larger
to turn effectively.
Attempt 3: Adjusted Gain (
- Fix: Increase
to make the robot turn faster. - Ensure: Wrap
using the atan2
function to keep the angles manageable. - Result: Smooth movement toward the goal with the proportional controller.
F.4) Demo: Behavior in Action
This approach was used in a competition:
- Robots moved toward the goal using the Go to Goal behavior.
- A simple Proportional Controller (
) was sufficient to handle the heading adjustments. - Success depended on properly tuned
and accurate handling of angles.
F.5) Key Takeaways
- Always handle angles carefully by wrapping them to
. - The proportional gain (
) significantly impacts the robot’s ability to reach the goal. - This approach is simple yet effective, especially when combined with additional behaviors like Avoid Obstacle.
G) The GRITS Simulator (Tuning Parameters in Matlab) (🎦 video 2.7)
Video: https://youtu.be/sJDfFgt3MrM
G.1) Overview: Tuning Parameters for Control Design
In control design, parameter tuning is a crucial step. Parameters like those in a PID controller are typically adjusted through testing and simulation.
Here, we focus on:
- Simulating the Go to Goal behavior.
- Using a PID regulator for heading control.
- Iteratively tuning the parameters to achieve desirable performance.
G.2) Matlab Simulation Setup
Robot and Environment
- Robot Model: Capira 3 differential drive mobile robot.
- Sensors:
- Infrared range sensors for obstacle detection.
- Wheel encoders for odometry (to estimate position and orientation).
- Simulator: A MATLAB-based tool, downloadable as:
- A standalone executable for easy interaction.
- A MATLAB package for customizations.
Initial Goal
- Robot Start Position: Arbitrary initial heading.
- Goal Position:
. - The task is to navigate to the goal using a PID controller.
G.2.1) Initial Control Parameters
- Proportional Gain (P):
- Integral Gain (I):
- Derivative Gain (D):
Observations
- The robot’s actual heading (blue line) overshot the desired heading (red dotted line).
- Although the robot eventually stabilized, the overshoot indicated poor control performance.
G.2.2) Refining Control Parameters
Adjustments
- Reduce Integral Gain: The high
was unnecessary, as precision was not a priority. - Set
to eliminate overshoot caused by integral windup.
- Set
- Keep P and D Gains:
: Maintains responsiveness. : No derivative action for simplicity.
Simulation Results
- The updated controller eliminated overshoot.
- Desired Heading and Actual Heading matched more closely.
- The robot reached the goal efficiently, confirming the parameters were functional.
G.3) Real Robot Implementation
Hardware Setup
- Robot: Capira 3 differential drive mobile robot.
- Sensors: Wheel encoders for odometry.
- Goal Location: A turquoise point in the environment.
Controller Parameters
- Same as in the final simulation:
, , .
Results
- The robot executed a smooth turn with minimal oscillation.
- Successfully navigated to the goal with stable performance.
- The real-world test confirmed the simulation results.
G.4) Key Takeaways: Simulation
- Simulation First: Simulations are invaluable for testing and refining control designs before deployment.
- Parameter Tuning:
- Excessive
can lead to overshoot. Reduce it unless precise tracking is essential. - Start with simple controllers (e.g., pure proportional) before introducing complexity.
- Excessive
- Real-World Validation: Always test controllers on actual hardware to confirm performance in dynamic conditions.
H) Introduction to Obstacle Avoidance Behaviors and Arbitration Mechanisms (🎦 video 2.8)
Video: https://youtu.be/bsdBFHMSI2E
H.1) Introduction: Obstacle Avoidance
-
Dynamic Duo of Robotics: Most mobile robots require two fundamental behaviors:
- Go to Goal: Drives the robot towards a specified target.
- Obstacle Avoidance: Prevents the robot from colliding with obstacles.
-
While Go to Goal has a straightforward direction, obstacle avoidance involves multiple possibilities:
- Pure avoidance.
- Combining avoidance with goal direction.
- Blending both behaviors.
H.2) Model Setup: Encountering Obstacles
Scenario
- Robot: Represented as a blue ball.
- Obstacle: Represented as a red object at position
. - Goal: Represented as a yellow object at position
.
Known Quantities
- The robot’s position:
. - The obstacle's position:
. - The goal's position:
.
H.2.1) Behavior Definitions: Obstacle Avoidance Directions
Obstacle Avoidance Directions:
- Pure Avoidance (Skittish/Paranoid):
- Move directly away from the obstacle.
- Desired heading:
- Here:
- Adding (
) ensures the robot moves in the opposite direction of the obstacle.
- Perpendicular Avoidance:
- Move perpendicular to the obstacle direction:
- Move perpendicular to the obstacle direction:
- Choice of Direction: Depends on the goal:
: Moves closer to the goal. : Moves further from the goal.
- Pure Go to Goal:
- Ignore the obstacle entirely and head directly to the goal:
- Ignore the obstacle entirely and head directly to the goal:
- Blended Approach:
- Combine goal-seeking with obstacle avoidance to generate a desired heading:
- Weights (
) and ( ) determine the influence of each behavior.
- Combine goal-seeking with obstacle avoidance to generate a desired heading:
H.3) Arbitration Mechanisms
When combining Go to Goal and Obstacle Avoidance, two approaches exist:
-
Winner Takes All (Hard Switch):
- Switch between behaviors based on the situation:
- Use Go to Goal when no obstacles are nearby.
- Use Obstacle Avoidance when close to an obstacle.
Advantages:
- Simpler analysis.
- Each behavior can be designed independently.
Disadvantages:
- Sudden switches can lead to inefficient or unnatural movements.
- Switch between behaviors based on the situation:
-
Blended Behaviors:
- Continuously combine behaviors to produce smooth transitions.
- Example:
- Steer slightly away from an obstacle while maintaining progress toward the goal.
Advantages:
- Smoother trajectories.
- More natural behavior.
Disadvantages:
- More complex to analyze and design.
H.4) Key Takeaways: Arbitration Mechanisms
- Flexibility in Design:
- There is no single correct way to handle obstacle avoidance. The choice depends on the application and environment.
- Analysis vs. Performance:
- Hard Switches: Easier to analyze but may reduce performance.
- Blended Behaviors: Improve performance but complicate analysis.
- Future Focus:
- Module 3 will revisit the behaviors and refine them using linear systems theory for a more systematic and formal design.
Conclusion
The combination of Go to Goal and Obstacle Avoidance forms the foundation for mobile robot navigation. Understanding and implementing arbitration mechanisms is critical for ensuring smooth and efficient robot movement.
I) Glue Lecture 2 - Robot Models and Feedback Control (🎦 video 2.9)
Video: https://youtu.be/-7erKJdb-6o
I.1) Key Topics: Module 2
- Differential Drive Model vs. Simplified Model
- Mapping Between Models
- Importance of Feedback Control
- Odometry and Wheel Encoders
- Practical Example
I.2) Differential Drive vs. Simplified Model
I.2.1) Differential Drive Model
- Used for implementing controllers on a robot.
- Inputs: Angular velocities of the wheels:
- Right wheel:
- Left wheel:
- Right wheel:
- Based on the actual physical constraints of the robot.
I.2.2) Simplified Model (Unicycle Model)
- Used for designing controllers.
- Inputs:
: Translational (linear) velocity. : Angular velocity.
- Easier to design controllers using this abstraction.
I.3) Mapping Between Models
To convert from
Example: Spinning in Place
, (constant angular velocity): - Interpretation:
- Right wheel moves forward, left wheel moves backward at equal magnitude.
- Result: The robot spins in place.
I.4) Importance of Feedback Control
I.4.1) Why Not Use a Perfect Model? (Open-Loop Systems)
- Real-world issues such as:
- Friction.
- Encoder inaccuracies.
- External disturbances (e.g., someone kicks the robot).
- Without feedback, errors accumulate:
- The robot veers off course.
- No correction mechanism.
I.4.2) Key Concept: Feedback Control (Closed-Loop-Systems)
- Feedback provides information about the robot’s actual position and orientation.
- Essential for minimizing error between the desired and actual state.
Relation to PID Control:
- Feedback is used to compute the error:
- Controllers like P, PI, and PID regulate this error.
I.5) Odometry and Wheel Encoders
How Wheel Encoders Work
- Encoders measure the ticks of each wheel:
- Total ticks per revolution:
- Distance per tick:
- Total ticks per revolution:
- Distance moved by each wheel:
Updating Robot’s State
Using odometry equations:
Where:(distance moved by the center of the robot).
I.5.1) Practical Example: Odometry
Scenario
- Initial Position:
- After 0.1 seconds:
- Right wheel: 10 ticks.
- Left wheel: 6 ticks.
- Wheel radius:
m. - Total ticks per revolution:
. - Wheelbase:
m.
Steps
-
Calculate distances moved by wheels:
-
Compute center distance:
-
Update state using odometry equations:
I.6) Key Takeaway: Why Use Encoders Instead of Perfect Models?
- Real-world deviations (e.g., friction, slippage) mean the robot doesn’t always follow the theoretical model.
- Encoders provide feedback to correct for these deviations and ensure accurate positioning.
J) Programming & Simulation (🎦 video 2.10)
Video: https://youtu.be/tjnCFrzdcO4
This week’s assignments involve:
- Transforming unicycle dynamics to differential drive dynamics.
- Implementing odometry to estimate the robot's position and orientation.
- Utilizing infrared sensors to measure distances to obstacles.
J.1) Simulator Structure
Quick Bot Overview:
- Drive Type: Two-wheel differential drive.
- Each wheel is controlled by an independent motor.
- Sensors:
- Wheel encoders:
- Measure the distance traveled by each wheel.
- Resolution: 32 ticks per revolution.
- Infrared sensors:
- Detect obstacles within 4 to 30 cm.
- Return voltage corresponding to distance.
- Wheel encoders:
The simulation involves several components working together at every time step:
- Timer Object inside the Simulator:
- Calls the
execute
function in the Supervisor.
- Calls the
- Supervisor (decision maker):
- Gathers sensor information from the robot (IR, Ticks).
- Selects a controller and sends sensor data, along with the robot's estimated position and orientation, to the controller (Inputs).
- Updates the robot’s position and orientation estimate.
- Controller:
- Computes linear and angular velocities (v,w).
- Converts these velocities to left and right wheel speeds (vel_r, vel_l).
- Robot:
- Receives wheel speed commands from the controller.
J.2) Assignment Breakdown
Part 1: Differential Drive Dynamics
Task: Convert linear and angular velocities to left and right wheel speeds.
Implementation:
- Function:
uni_to_diff
inDifferentialDrive.m
.
- Inputs:
- Linear velocity (
). - Angular velocity (
).
- Linear velocity (
- Outputs:
- Left wheel speed.
- Right wheel speed.
Skeleton Code:
- Provides R
(wheel radius) and L
(distance between wheels).
- Use these to calculate the required speeds.
Part 2: Odometry
Task: Estimate the robot's position and orientation using wheel encoder data.
Implementation:
- Function:
update_odometry
inQBSupervisor.m
.
- Steps:
- Retrieve current wheel encoder ticks.
- Recall previous wheel encoder ticks.
- Retrieve the current position and orientation estimate.
- Use constants:
R
(wheel radius).L
(distance between wheels).- Meters per encoder tick.
- Calculate:
, (change in position). (change in orientation).
- Update the robot’s position and orientation.
- Save the current tick count for the next iteration.
Part 3: Infrared Sensor Distance Conversion
Task: Convert sensor readings to distances.
Note: non linear function,
Implementation:
- Function:
get_ir_distances
inQuickBot.m
.
- Steps:
- Convert integer sensor readings (200–1375) to voltage.
- Formula:
.
- Formula:
- Use MATLAB’s
polyfit
function to fit a fifth-order polynomial to the sensor data. - Use
polyval
with the polynomial coefficients to convert voltage to distance (in meters).
- Convert integer sensor readings (200–1375) to voltage.
- Sensor readings range from 0.4 to 2.75 V, corresponding to 4–30 cm.
J.3) Testing and Debugging
-
Controller Provided: A
Go-to-Angle
controller (proportional regulator).- Drives the robot to a specified angle.
- Angle is set in the
QBSupervisor.m
constructor.
-
Example:
- Default angle:
(45°). - Robot drives at 45° relative to the x-axis until it collides with an obstacle.
- Default angle:
Example Simulation:
Tips for Success:
- Read the Manual:
- Refer to Week 2’s section in the manual for detailed guidance.
- Use Debugging Tools:
- Enable and add
fprintf
statements in the provided code to monitor intermediate values like position estimates.
- Enable and add
- Visual Validation:
- Observe the robot's movement in the simulator to ensure it behaves as expected.
K) Hardware Notes (🎦 video 2.11)
Video: https://youtu.be/16RsgdwjROE
Z) 🗃️ Glossary
File | Definition |
---|