Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

921 kinematics pose estimation #1089

Merged
merged 29 commits into from
Feb 16, 2023
Merged
Changes from 1 commit
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
1ce5b00
Add tachometer, odometer and kinematics part
Ezward Jan 1, 2023
deeb6fc
refactor pose estimation into a single part
Ezward Jan 8, 2023
d31b163
comment out logging of pose to quiet the console
Ezward Jan 8, 2023
9710c16
add arduino encoder sketches
Ezward Jan 16, 2023
6d66d2c
remove unicode characters that prevent compilation of arduino sketch
Ezward Jan 17, 2023
ff95fdf
clean up comments a little
Ezward Jan 17, 2023
e2a9a54
Add more documentation to the quadrature_encoder.ino sketch
Ezward Jan 18, 2023
325e89b
Add interrupt mode to the mono encoder
Ezward Jan 24, 2023
a5c6a44
Remove spurious unicode beta character
Ezward Jan 24, 2023
ae4ab8f
removed digital write high in mono encoder
Ezward Jan 24, 2023
8f2f859
Fix syntax error if only using one channel in int mode
Ezward Jan 26, 2023
e6eb5cf
Added a quadrature encoder sketch with no libraries
Ezward Jan 28, 2023
162ff35
Fix bug in mono encoder sketch
Ezward Jan 28, 2023
5d05b11
Fix bug in quadrature nolib sketch
Ezward Jan 28, 2023
a4ede0a
minor change to quadrature nolib
Ezward Jan 28, 2023
896cc26
Updated quadrature_encoder.ino to not require library
Ezward Jan 31, 2023
1cf569d
fix merge error in path_follow.py
Ezward Feb 4, 2023
a90421d
Fix RPi_GPIO_Servo part so it does not need GPIO in constructor
Ezward Feb 5, 2023
92af322
added non-threaded run() to UnicyclePose and BicyclePose for testing
Ezward Feb 8, 2023
4e6c371
Improved accuracy of MockEncoder by propagating fractional ticks
Ezward Feb 8, 2023
6d4f506
Updated add_odometry() so we could add as non-threaded for testing.
Ezward Feb 8, 2023
9f2ab20
Vehicle loop prints out number of iterations and total time
Ezward Feb 8, 2023
e9cac78
Rewrite of the kinematics unit tests
Ezward Feb 8, 2023
0cda9b0
Adjust bicycle kinematics to use front wheel reference
Ezward Feb 9, 2023
a1d4f78
relax orientation test to 3% accuracy
Ezward Feb 9, 2023
024fc0f
updated based on PR feedback
Ezward Feb 9, 2023
0ae8db9
removed hard-coded logging level
Ezward Feb 12, 2023
ee22a1b
Update vehicle.py
Ezward Feb 13, 2023
78711a7
Update setup.py version="4.4.dev5"
Ezward Feb 13, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
Add more documentation to the quadrature_encoder.ino sketch
  • Loading branch information
Ezward committed Feb 14, 2023
commit e2a9a54ff0463127c53f09e478f79ae816013f8f
33 changes: 25 additions & 8 deletions arduino/quadrature_encoder/quadrature_encoder.ino
Original file line number Diff line number Diff line change
Expand Up @@ -19,18 +19,25 @@
* If you have a different microcontroller
* then see your datasheet for which pins are interrupt
* capable.
*
* Adds command for on-demand sending of encoder value
* and continuous sending with provided delay.
* Returns timestamp along with encoder ticks.
*
* Implements the r/p/c command protocol
* The sketch implements the r/p/c command protocol
* for on-demand sending of encoder value
* and continuous sending with provided delay.
* See the comment in the loop below for details.
* commands are send one per line (ending in '\n')
* 'r' command resets position to zero
* 'p' command sends position immediately
* 'c' command starts/stops continuous mode
* - if it is followed by an integer,
* then use this as the delay in ms
* between readings.
* - if it is not followed by an integer
* then stop continuous mode
*
* Sends the encoder ticks and a timestamp
* as a comma delimited pair: ticks,timeMs
* In a dual encoder setup the second encoder values
* as separated from the first by a semicolon: ticks,timeMs;ticks,timeMs
*
*/
#include <Arduino.h>
Expand All @@ -45,10 +52,20 @@
#define DUAL_ENCODERS

#ifdef DUAL_ENCODERS
#define ENCODER_CLK_PIN (2) // clock input pin for first encoder
//
// Note that if this is for a differential drive configuration
// then the encoders are generally oriented oppositely, so when
// one is turning clockwise the other is turning counter-clockwise.
// Therefore we want the data and clock pins to be hooked up oppositely
// for each encoder. This can be achieved by reversing the connections
// on the right encoder, so that the data pin of the encoder is
// assigned the ENCODER_2_CLK_PIN and the clock pin of the encoder
// is assigned to ENCODER_2_DT_PIN.
//
#define ENCODER_CLK_PIN (2) // clock input pin for first encoder (left wheel)
#define ENCODER_DT_PIN (4) // data input pin for first encoder
#define ENCODER_2_CLK_PIN (3) // clock input pin for second encoder
#define ENCODER_2_DT_PIN (5) // data input pin for second encoder
#define ENCODER_2_CLK_PIN (3) // input pin for second encoder (right wheel, see above)
#define ENCODER_2_DT_PIN (5) // input pin for second encoder
#else
#define ENCODER_CLK_PIN (2) // clock input pin for first encoder
#define ENCODER_DT_PIN (3) // data input pin for first encoder
Expand Down