Controlling Servos up to 4 precision digit

Greetings,

I’m doing a hexapod for my thesis project, and I need to move my servos up to 4 precision digits to move my robot to the desired position, is there anyway to increase the range of my signal resolution ???

I use TowerPro SG5010 that works in 400-2200 microseconds, which means I can control up to 1 precision digit 2200-400 = 1800, 1 microseconds = 0.1 Degrees

I use the mini maestro 18 channel in serial communication with Arduino uno, therefore, floating points in binary is not an option, I’ve also monitor the position (using get position protocol) during floating point signals (xx.25 , xx.50 , xx.75) and they all return to the rounded down, xx microseconds

Thank You,
Heggi

Hello.

You don’t need to do any floating point calculations to use the Maestro, and you probably shouldn’t. The Maestro’s native units are 0.25 microseconds, and that is the resolution it supports. If you set the target to a value of 6001, that corresponds 1500.25 microseconds. For information about the serial Set Target command which allows you to send these target values to the Maestro’s serial interface, see this page:
pololu.com/docs/0J40/5.e

–David

the problem is, my thesis requires my robot to moves in mm, and corresponding with my mechanical design, the inverse kinematics calculation produce floating points, in which every mm has a very small differences in motor’s position in degree…

I’ve tried to rounded it (up or down) but the result is way off the initial target…

Well, you may want to check that your servo will use higher resolution. From what I’ve read, analog servos will be more in the range of .5 to 6us resolution (also known as dead band), which would mean that anything you gain from a higher res servo controller is lost at the servo.

Standard analog servos are not high precision devices. Digital servos, on the other hand, can be programmed to 0 dead band (Theoretical infinite resolution). It wont be perfect, but it will be much better than any analog servo.

If you really want to have extremely high res servo control, you might consider programming a fast microcontroller to do it. A Atmega running at 10-20Mhz will probably be able to give .1us res. But you would have to have a timer running at 100Mhz for .01us resolution, and that is rare in hobby microcontrollers.

The Phidgets controller claims 83.3ns (.0833us) res, at 15bits. Generally though, the .25us res from the micro/mini Maestros is considered very high.

For the kind of precision you are describing, you may want to use something else. A geared down stepper motor might do what you need. It wont be fast, but it will have lots of torque and precision. Or you may want to take a look at industrial “servos” (which are really nothing like hobby/RC servos).

As a side note, for translation into physical movement, it is much easier to work with integer values and smaller units instead of floating point. Remember that microcontrollers think in binary.

hi Darth Maker, for the hardware, I don’t really focus in it, cause digital servos is quite expensive here, so I’ll bear with the unavoidable error from analog servo…

after reading it again and again, I finally realize that the resolution in mini maestro can represent up to three precision digit, although there are only x.x00, x.x25, x.x50, and x.x75, so I tried to round the values from the kinematics calculation into the nearest available options of those available three precision digit, and it turns out that the output is not bad, the error is less than 0.1 mm, which is very acceptable :smiley:

actually, I’ve another question regarding serial communication, I’ve been trying to monitor the position of my motor during it’s movement, so I thought I’ll use the Get Moving State and Get Position command, but I failed to get the output as I wanted, this is my program in Arduino Uno :

#include <SoftwareSerial.h>

#define rxPin 2
#define txPin 3

SoftwareSerial servo = SoftwareSerial(rxPin, txPin);

void setup()
{
  pinMode(rxPin, INPUT);
  digitalWrite(txPin, HIGH);
  pinMode(txPin, OUTPUT);
  
  Serial.begin(9600);
  servo.begin(9600);
  
  move400();
}

byte getstate()
{
byte state;
servo.write(0x93);
state = servo.read();
return state;
}

byte getpos()
{
byte posval1;
byte posval2;
byte pos;
servo.write(0x90);
servo.write(0x11);
posval1 = servo.read(); 
posval2 = servo.read();
pos = ((posval2 * 0x100) + posval1);
return pos;
}

void move2200()
{
servo.write(0x84);
servo.write(0x11);
servo.write(0x18);
servo.write(0x11);
}

void move400()
{
servo.write(0x84);
servo.write(0x11);
servo.write(0x10);
servo.write(0x03);
}

void loop()
{
byte posstate;
byte movestate;
move2200();
movestate = getstate();
posstate = getpos();
Serial.print(" pos ");
Serial.println(posstate);
Serial.print(" state ");
Serial.println(movestate);
move400();
Serial.print(" pos ");
Serial.println(posstate);
Serial.print(" state ");
Serial.println(movestate);
}

the problem is the posval2 value is saved in movestate, so it makes the posstate consist of posval1 and state

I can’t show the output from the serial monitor now, I’ll upload it as soon as possible

thanks,

Heggi

Well, there are a couple errors in your code.

First, you don’t have a delay(); after moving the servo. So the code rapidly switches between each position, and the servo will never make it to either.

Next, you are forgetting to call getstate() and getpos() after the second servo position. So you are printing the same values twice, and the values will always be related to the first position, never the second.

In getpos() you are combing the posval1 and posval2 into a 16bit number, but your pos variable and function are a byte, so it gets truncated back down to an 8bit. Also, posstate in loop() is declared a byte, when you need it to be a 16bit int. For each of these, you should declare them “unsigned int”, since you are only working with positive numbers.

Then, you need to change the values from 2200 and 400 to 8800 and 1600. The Maestros operate with .25us units, so 1600*.25 is 400us.

To receive the values in getpos() and getstate(), you should check servo.available() with a while statement. Otherwise you may be reading an empty buffer. This is shown below in my version of your code.

I don’t have a Mini Maestro, but I do have a Micro. I changed the servo number to 0 to work with it. I also made a couple minor changes for my own readability.

#include <SoftwareSerial.h>

#define rxPin 2
#define txPin 3

SoftwareSerial servo = SoftwareSerial(rxPin, txPin);

void setup()
{
//    pinMode(rxPin, INPUT);
//    digitalWrite(txPin, HIGH);    //Writing to a pin before setting it to be an
                                                //output does not actually set the pinstate.
                                                //It instead writes to the pullup register.
//    pinMode(txPin, OUTPUT);    //You don't need these lines.  Software Serial sets these.


    Serial.begin(9600);
    servo.begin(9600);
    delay(100);    //Never hurts to put in a short start up delay.  Makes sure
                        //that the Maestro is on before sending serial to it.

    move400();
    delay(500);    //Wait for servo to move to position.
}

byte getstate()
{
    byte state;
    servo.write(0x93);
    while(servo.available() < 1);  //Wait for 1 byte to be available in the buffer.
    state = servo.read();             //SoftwareSerial::read() is non-blocking in 1.0.  If
                                               //there is nothing in the buffer it returns -1.
    return state;
}

unsigned int getpos()    //The function needs to be an int if you want to return values greater
{                                //than 255.
    byte posval1;
    byte posval2;
    unsigned int pos;    //Also needs to handle int sized numbers
    servo.write(0x90);
    servo.write(byte(0));
    while(servo.available() < 2);    //wait for 2 bytes to be available in the buffer.
    posval1 = servo.read();
    posval2 = servo.read();
    pos = ((posval2 << 8) + posval1);    //I only changed this line for my own
                                                      //readability, what you had is fine.
    return pos;
}

void move2200()
{
    servo.write(0x84);
    servo.write(byte(0));   //Writing a 0 will give an ambiguous error if you don't cast it.
    servo.write(0x60);       //These numbers need to make 8800 for a time of 2200us.  Units are in .25us
    servo.write(0x44);
}

void move400()
{
    servo.write(0x84);
    servo.write(byte(0));
//    servo.write(0x10);    //These were the values you had
//    servo.write(0x03);
    servo.write(0x64);
    servo.write(0x0C);
}

void loop()
{
    unsigned int posstate;    //Again, this variables needs to handle numbers larger than 255.
    byte movestate;
    move2200();
    delay(500);      //This lets the servo move to position.  You can make it
                          //shorter and getstate() will return a 1.
    movestate = getstate();
    posstate = getpos();
    Serial.print(" pos1 ");
    Serial.print(posstate);
    Serial.print("\t\tstate1 ");     //The "\t" character is a tab.
    Serial.println(movestate);    //I changed the output to make it more readable.
    move400();
    delay(500);
    movestate = getstate();
    posstate = getpos();
    Serial.print(" pos2 ");
    Serial.print(posstate);
    Serial.print("\t\tstate2 ");
    Serial.println(movestate);
}

This is compiled and tested in Arduino 1.0. To work in 0023 and older, you would need to use new software serial instead of software serial. That replacement was made in 1.0.

I get position values of 8000 and 3968. I those are the upper and lower limits set for my Maestro.

@Darth Maker
thanks a lot, that code solves lots of my problem, including the serial data representation
and a little modification make me able to have a live feed of my servo’s position, this is my final code

#include <SoftwareSerial.h>

#define rxPin 2
#define txPin 3

SoftwareSerial servo = SoftwareSerial(rxPin, txPin);

void setup()
{
    Serial.begin(9600);
    servo.begin(9600);
    delay(100);    
    move400();
    delay(500);    
}

byte getstate()
{
    byte state;
    servo.write(0x93);
    while(servo.available() < 1);  
    state = servo.read();             
                                               
    return state;
}

unsigned int getpos()    
{                                
    byte posval1;
    byte posval2;
    unsigned int pos;    
    servo.write(0x90);
    servo.write(byte(0));
    while(servo.available() < 2);    
    posval1 = servo.read();
    posval2 = servo.read();
    pos = ((posval2 << 8) + posval1);    
                                                      
    return pos;
}

void move2200()
{
    servo.write(0x84);
    servo.write(byte(0));   
    servo.write(0x60);       
    servo.write(0x44);
}

void move400()
{
    servo.write(0x84);
    servo.write(byte(0));
    servo.write(0x64);
    servo.write(0x06);
}

void loop()
{
    unsigned int posstate;    
    byte movestate;
    move2200();
    delay(10);     
                         
    movestate = getstate();
    while (movestate == 1)
    {
      posstate = getpos();
    Serial.print(" pos1 ");
    Serial.print(posstate);
    Serial.print("\t\tstate1 ");     
    Serial.println(movestate);    
    movestate = getstate();
    }
    delay(100);
    move400();
    delay(10);
    movestate = getstate();
    
    while (movestate == 1)
    {
      posstate = getpos();
    Serial.print(" pos1 ");
    Serial.print(posstate);
    Serial.print("\t\tstate1 ");    
    Serial.println(movestate);    
    movestate = getstate();
    }
    delay(100);
    
}