Speed sensors instead of wheel encoders (Gear-motor-encoder from Neato XV-11)

474 views
Skip to first unread message

Igor Andrusyk

unread,
Jun 11, 2018, 5:26:47 PM6/11/18
to LINOROBOT
Hello. I have two gear-motor-encoder from Neato XV-11. But this motors actually not has ancoders. He has speed sensors on Hall effect. 
He has only 5 wires from every motor (not 6 like in real motor-encoder). That's mean I can measure only speed and can't measure direction rotation.


Questions: What I must change in code for use this motors?? It's possible? Maybe I can use IMU sensor for check direction or any method for this?? Do you have any idea? Thank's.
PS: Sorry for my English:)

Wheels.jpg

Dominic Schmidt

unread,
Jun 11, 2018, 6:19:15 PM6/11/18
to LINOROBOT

Hello Igor,

the easiest thing in my opinion would be to buy a dual channel hall sensor to replace the single channel one on your encoder. They are really cheap and you already have the magnetic disc on your motor.


You can put it next to the old one and it will work fine.


You can try to change the firmware instead but it's always nice to have a full sensor for debugging.

Igor Andrusyk

unread,
Jun 12, 2018, 3:03:27 AM6/12/18
to LINOROBOT
Dominic Schmidt big thank's, bro. I tryed doing this.

蕭丞煜

unread,
Apr 30, 2019, 6:00:46 AM4/30/19
to LINOROBOT
May I ask if the encoder of this motor will measure square wave directly?
Or do you want to get the motherboard of the sweeper to work?

Adrian Stucker

unread,
May 17, 2019, 5:38:55 PM5/17/19
to LINOROBOT
Any idea where to find one of these A3423s? All I can find are 3pin(single channel) hall sensors. I cooked mine that were included on the motor with a short circuit.

Thanks!

Dominic Schmidt

unread,
May 17, 2019, 6:01:22 PM5/17/19
to LINOROBOT
Try looking for "hall effect ic". I found these on aliexpress. There are many different models so I just picked the first I could find with a proper datasheet.

Sandor Czettner

unread,
Sep 23, 2019, 8:10:38 AM9/23/19
to LINOROBOT
I know this is an old thread, but I had the same problem and I solved it this way:

Set the MOTOR*_ENCODER_A and MOTOR*_ENCODER_B pins to the one and only Holzer signal pin, then add this to firmware.ino in moveBase(), replacing the getRPM() calls:

    //get the current speed of each motor
    int current_rpm1 = motor1_encoder.getRPM();
    if (req_rpm.motor1 < 0) {
        dir1 = -1;
    } else if (req_rpm.motor1 > 0) {
        dir1 = 1;
    }
    if (dir1 < 0) current_rpm1 *= -1;
    int current_rpm2 = motor2_encoder.getRPM();
    if (req_rpm.motor2 < 0) {
        dir2 = -1;
    } else if (req_rpm.motor2 > 0) {
        dir2 = 1;
    }
    if (dir2 < 0) current_rpm2 *= -1;
    int current_rpm3 = motor3_encoder.getRPM();
    int current_rpm4 = motor4_encoder.getRPM();

Also add this to the top of the file:

int dir1, dir2;

Basically what it's doing, is trying to guess the direction of the motor based on the previous direction command. This is an ugly solution and it may need a rewrite to use a single signal, but it works for me.
Reply all
Reply to author
Forward
0 new messages