Legacy Forum: Preserving Nearly 20 Years of Community History - A Time Capsule of Discussions, Memories, and Shared Experiences.

changing the code in the MR-C3024

Hitec robotics including ROBONOVA humanoid, HSR-8498HB servos, MR C-3024 Controllers and RoboBasic
223 postsPage 4 of 151, 2, 3, 4, 5, 6, 7 ... 15
223 postsPage 4 of 151, 2, 3, 4, 5, 6, 7 ... 15

Post by DanAlbert » Tue Sep 26, 2006 3:23 am

Post by DanAlbert
Tue Sep 26, 2006 3:23 am

Progress Report:

Since I replaced the ATMEGA128 with a new chip I have.

Both serial ports working via ISR.
The speaker can generate sounds.
And most importantly...All 24 servos PWM with 5 uSec (or 1 degree) increments. All 24 servos start at almost the same time. Since this is an 8 bit processor you need to assign values to ports A,B and C one instruction apart.

Since everything is done in ISRs I can play a tune while moving servos and receiving data. Duh...what a concept. Hitec makes great servos, but when it comes to software they don't have a clue.

For those that are still reading this....and want the gorey details.

This would be a lot easier if Hitec had used a 16MHz or even a 14.7456 XTAL. With only 5 uSecs to work with, at 7.3728 MHz ... well lets do the math.

To get 200 degrees in a 1 mSec PWM pulse, thats 5 uSecs per degree.

1/7372800 = .000,000,1356336..secs per cycle
.000,005 / .000,000,1356 = 36.8 cycles in 5 uSecs.

This is all ya get at 7 MHz.
the overhead on the ISR just in/out and SREG push/pop about 11 cycles.
not much time left to do anything.

I set up the data for all 24 servos during the deadband time.
This is an array of 96 pieces of data grouped in a structure of 4 bytes.(24 * 4 = 96) the first byte is the time(OCR1A setting) until the next change of state of any of ports A,B and C bits. The next three bytes are the values of ports A,B and C at that timer match.

I have two timers. Timer 0 counts off mSecs and Timer 1 gets reset at each ISR call (when OCR1A = TCNT1) with a max resolution of 5 uSecs where I load the state of Ports A,B and C.
At 0 mSec I set all the servo channels high.
At 1 mSec 1 start the faster Timer 1.
It tics off as many times as necessary to bring all the lines to low.
Since some servos have the same setting this can be less than 24.
At 2 mSec I stop Timer 1.

Heres the ISRs
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// ISR mSec routine
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
ISR(TIMER0_COMP_vect, ISR_BLOCK)
{
static U8 mSecServoCounter;
mSecServoCounter++;
if(mSecServoCounter >= 20){
mSecServoCounter = 0;
PORTA = 0xFF; //Servos S7 - S0
PORTB = 0xFF; //Servos S15 - S8
PORTC = 0xFF; //Servos S23 - S16
}
else if(mSecServoCounter == 1){
ptrTrailingEdge = &ServoTrailingEdgeList[0];
TEhigh = (((U16)ptrTrailingEdge >> 8 ) & 0xff);
TElow = ((U16)ptrTrailingEdge & 0xff);
asm ("movw r30,r16");
noServoUpdate = 1;
TIMSK |= OCIE1A; // enable output compare interrupt
OCR1A = 1;
TCNT1 = 0; // reset counter for accurate .5 uSec count
}
// at two mSecs all servos should already be off (failsafe)
else if(mSecServoCounter == 2){
PORTA = 0x00; //turn off all servos
PORTB = 0x00; //turn off all servos
PORTC = 0x00; //turn off all servos
TIMSK &= ~OCIE1A; // disable output compare interrupt
noServoUpdate = 0;
}
ms_count++;
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// ISR Timer 1A individual trailing edge PWM for each servo
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
ISR(TIMER1_COMPA_vect,ISR_NAKED)
{
asm volatile (
"cli\n\t"
"in R18,__SREG__\n\t"
"ld R19, Z+\n\t"
"out 42, R19\n\t"
"ld R19, Z+\n\t"
"out 27, R19\n\t"
"ld R19, Z+\n\t"
"out 24, R19\n\t"
"ld R19, Z+\n\t"
"out 21, R19\n\t"
"in R19,55\n\t"
"sbr R19,16\n\t"
"out 54,R19\n\t"
"clr R0\n\t"
"out __SREG__,r18\n\t"
"reti\n\t"
);
}


I've posted this code in the hope that someone else will help with this project. There is still a great deal of work to be done.

We should set up an open source area on this site for posting code updates.


Next.....I2C and EEPROM

I want to store servo "zero" settings and servo positions.
Then come up with a method for dynamic movements.
Progress Report:

Since I replaced the ATMEGA128 with a new chip I have.

Both serial ports working via ISR.
The speaker can generate sounds.
And most importantly...All 24 servos PWM with 5 uSec (or 1 degree) increments. All 24 servos start at almost the same time. Since this is an 8 bit processor you need to assign values to ports A,B and C one instruction apart.

Since everything is done in ISRs I can play a tune while moving servos and receiving data. Duh...what a concept. Hitec makes great servos, but when it comes to software they don't have a clue.

For those that are still reading this....and want the gorey details.

This would be a lot easier if Hitec had used a 16MHz or even a 14.7456 XTAL. With only 5 uSecs to work with, at 7.3728 MHz ... well lets do the math.

To get 200 degrees in a 1 mSec PWM pulse, thats 5 uSecs per degree.

1/7372800 = .000,000,1356336..secs per cycle
.000,005 / .000,000,1356 = 36.8 cycles in 5 uSecs.

This is all ya get at 7 MHz.
the overhead on the ISR just in/out and SREG push/pop about 11 cycles.
not much time left to do anything.

I set up the data for all 24 servos during the deadband time.
This is an array of 96 pieces of data grouped in a structure of 4 bytes.(24 * 4 = 96) the first byte is the time(OCR1A setting) until the next change of state of any of ports A,B and C bits. The next three bytes are the values of ports A,B and C at that timer match.

I have two timers. Timer 0 counts off mSecs and Timer 1 gets reset at each ISR call (when OCR1A = TCNT1) with a max resolution of 5 uSecs where I load the state of Ports A,B and C.
At 0 mSec I set all the servo channels high.
At 1 mSec 1 start the faster Timer 1.
It tics off as many times as necessary to bring all the lines to low.
Since some servos have the same setting this can be less than 24.
At 2 mSec I stop Timer 1.

Heres the ISRs
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// ISR mSec routine
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
ISR(TIMER0_COMP_vect, ISR_BLOCK)
{
static U8 mSecServoCounter;
mSecServoCounter++;
if(mSecServoCounter >= 20){
mSecServoCounter = 0;
PORTA = 0xFF; //Servos S7 - S0
PORTB = 0xFF; //Servos S15 - S8
PORTC = 0xFF; //Servos S23 - S16
}
else if(mSecServoCounter == 1){
ptrTrailingEdge = &ServoTrailingEdgeList[0];
TEhigh = (((U16)ptrTrailingEdge >> 8 ) & 0xff);
TElow = ((U16)ptrTrailingEdge & 0xff);
asm ("movw r30,r16");
noServoUpdate = 1;
TIMSK |= OCIE1A; // enable output compare interrupt
OCR1A = 1;
TCNT1 = 0; // reset counter for accurate .5 uSec count
}
// at two mSecs all servos should already be off (failsafe)
else if(mSecServoCounter == 2){
PORTA = 0x00; //turn off all servos
PORTB = 0x00; //turn off all servos
PORTC = 0x00; //turn off all servos
TIMSK &= ~OCIE1A; // disable output compare interrupt
noServoUpdate = 0;
}
ms_count++;
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// ISR Timer 1A individual trailing edge PWM for each servo
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
ISR(TIMER1_COMPA_vect,ISR_NAKED)
{
asm volatile (
"cli\n\t"
"in R18,__SREG__\n\t"
"ld R19, Z+\n\t"
"out 42, R19\n\t"
"ld R19, Z+\n\t"
"out 27, R19\n\t"
"ld R19, Z+\n\t"
"out 24, R19\n\t"
"ld R19, Z+\n\t"
"out 21, R19\n\t"
"in R19,55\n\t"
"sbr R19,16\n\t"
"out 54,R19\n\t"
"clr R0\n\t"
"out __SREG__,r18\n\t"
"reti\n\t"
);
}


I've posted this code in the hope that someone else will help with this project. There is still a great deal of work to be done.

We should set up an open source area on this site for posting code updates.


Next.....I2C and EEPROM

I want to store servo "zero" settings and servo positions.
Then come up with a method for dynamic movements.
DanAlbert
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 70
Joined: Fri Feb 04, 2005 1:00 am

Post by limor » Tue Sep 26, 2006 11:20 am

Post by limor
Tue Sep 26, 2006 11:20 am

Dan, I am very impressed!

I dont understand the assembly code. :oops:

but i assume in C it would look like this ?

Code: Select all
ISR(TIMER1_COMPA_vect) {
    PORTA=*pwm++;
    PORTB=*pwm++;
    PORTC=*pwm++;
    OCR1A=*pwm++;
}


where pwm is the array of 4*24 bytes

I'll set up a project in sourceforge.net for this code and also for some Bioloid code that I and others are working on.


BTW: have you thought of changing the oscilator to a 16mhz one and soldering a atmega128 that runs at 16mhz ?
Dan, I am very impressed!

I dont understand the assembly code. :oops:

but i assume in C it would look like this ?

Code: Select all
ISR(TIMER1_COMPA_vect) {
    PORTA=*pwm++;
    PORTB=*pwm++;
    PORTC=*pwm++;
    OCR1A=*pwm++;
}


where pwm is the array of 4*24 bytes

I'll set up a project in sourceforge.net for this code and also for some Bioloid code that I and others are working on.


BTW: have you thought of changing the oscilator to a 16mhz one and soldering a atmega128 that runs at 16mhz ?
limor
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 1845
Joined: Mon Oct 11, 2004 1:00 am
Location: London, UK

Post by DanAlbert » Tue Sep 26, 2006 12:11 pm

Post by DanAlbert
Tue Sep 26, 2006 12:11 pm

Hi Limor,
More like:

ISR(TIMER1_COMPA_vect) {
OCR1A=*pwm++;
PORTA=*pwm++;
PORTB=*pwm++;
PORTC=*pwm++;
}
The order is not relevant since the routine exits before OCR1A = TCNT1, the next 5 uSec timer tic, and if it did you would not be able to keep up anyway.

However if you compile this and look at the code you will find that it generates twice as many instructions. You also need to do some tricks to prevent needing to push and pop so many registers.

register U8 TEhigh asm("r17");
register U8 TElow asm("r16");
register U8 STATUSreg asm("r18");
register U8 ISRtemp asm("r19");

as well compiler options --ffixed-r?? where ?? = 16,17,18,19,30 and 31.
to prevent the C compiler from using these registers.

Sure, I have a 16MHZ Olimex board that would work too, but my objective is to allow people to reload the software on their existing boards without having to solder anything. Of course this depends on whether or not we can break into the secret bootloader. I am sure there is a backdoor. Nobody with half a brain would make thousands of boards that could have a potential bug that would require all the boards to be trashed.


I-bot, could you post the disassembled code. It may provide some clues.

Thanks,
Dan
Hi Limor,
More like:

ISR(TIMER1_COMPA_vect) {
OCR1A=*pwm++;
PORTA=*pwm++;
PORTB=*pwm++;
PORTC=*pwm++;
}
The order is not relevant since the routine exits before OCR1A = TCNT1, the next 5 uSec timer tic, and if it did you would not be able to keep up anyway.

However if you compile this and look at the code you will find that it generates twice as many instructions. You also need to do some tricks to prevent needing to push and pop so many registers.

register U8 TEhigh asm("r17");
register U8 TElow asm("r16");
register U8 STATUSreg asm("r18");
register U8 ISRtemp asm("r19");

as well compiler options --ffixed-r?? where ?? = 16,17,18,19,30 and 31.
to prevent the C compiler from using these registers.

Sure, I have a 16MHZ Olimex board that would work too, but my objective is to allow people to reload the software on their existing boards without having to solder anything. Of course this depends on whether or not we can break into the secret bootloader. I am sure there is a backdoor. Nobody with half a brain would make thousands of boards that could have a potential bug that would require all the boards to be trashed.


I-bot, could you post the disassembled code. It may provide some clues.

Thanks,
Dan
DanAlbert
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 70
Joined: Fri Feb 04, 2005 1:00 am

Post by bauermech » Tue Sep 26, 2006 4:23 pm

Post by bauermech
Tue Sep 26, 2006 4:23 pm

Dan, is it possible to increase the sevo resolution w/o taking away too much more processing power? 1 deg. is a pretty big chunk, and at slow positioning speeds the RN-1 is quite choppy... just a thought. :D
Dan, is it possible to increase the sevo resolution w/o taking away too much more processing power? 1 deg. is a pretty big chunk, and at slow positioning speeds the RN-1 is quite choppy... just a thought. :D
bauermech
Site Admin
Site Admin
User avatar
Posts: 318
Joined: Sat Feb 04, 2006 1:00 am
Location: Defiance, Ohio, USA

Post by DanAlbert » Wed Sep 27, 2006 1:08 am

Post by DanAlbert
Wed Sep 27, 2006 1:08 am

A faster XTAL (16MHz) would give you the ability to do at least 1/2 degree stepping. Maybe 1/3 degree. I can't find any info on servo resolution for the Hitecs. Is there a limit?

By choppy do you mean that the servo moves too much with 1 degree?
A faster XTAL (16MHz) would give you the ability to do at least 1/2 degree stepping. Maybe 1/3 degree. I can't find any info on servo resolution for the Hitecs. Is there a limit?

By choppy do you mean that the servo moves too much with 1 degree?
DanAlbert
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 70
Joined: Fri Feb 04, 2005 1:00 am

Post by bauermech » Wed Sep 27, 2006 9:24 am

Post by bauermech
Wed Sep 27, 2006 9:24 am

By choppy do you mean that the servo moves too much with 1 degree?


Yup, when you set the speed below oh... 5 or so, the servos jitter while transitioning.
By choppy do you mean that the servo moves too much with 1 degree?


Yup, when you set the speed below oh... 5 or so, the servos jitter while transitioning.
bauermech
Site Admin
Site Admin
User avatar
Posts: 318
Joined: Sat Feb 04, 2006 1:00 am
Location: Defiance, Ohio, USA

Post by DanAlbert » Wed Sep 27, 2006 12:57 pm

Post by DanAlbert
Wed Sep 27, 2006 12:57 pm

I would like to look at that on my logic analyzer.
It is very possible that their pulse width is fluctuating.
Who knows what they are sending.

The slower you go, the more steps it needs to make.
If the resolution of the steps is too small the servo may jitter trying to find a fractional step position it can never attain.
This could be inside the servo or in the MR-C3024.

Given the usual good quality of their servos vs their "Basic" I would guess the issue is the MR-C3024 software.

Either way we should be able to fix that is software.

At some point I'll try to reproduce the symptom.
Unfortunatly I only have one MR-C3024 and it has my new chip and program.

Dave said he would send me a spare board that I can use for testing.
When I get it I'll try what you say.
Please send me an some example code that causes the problem.
I would like to look at that on my logic analyzer.
It is very possible that their pulse width is fluctuating.
Who knows what they are sending.

The slower you go, the more steps it needs to make.
If the resolution of the steps is too small the servo may jitter trying to find a fractional step position it can never attain.
This could be inside the servo or in the MR-C3024.

Given the usual good quality of their servos vs their "Basic" I would guess the issue is the MR-C3024 software.

Either way we should be able to fix that is software.

At some point I'll try to reproduce the symptom.
Unfortunatly I only have one MR-C3024 and it has my new chip and program.

Dave said he would send me a spare board that I can use for testing.
When I get it I'll try what you say.
Please send me an some example code that causes the problem.
DanAlbert
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 70
Joined: Fri Feb 04, 2005 1:00 am

Post by bauermech » Wed Sep 27, 2006 4:37 pm

Post by bauermech
Wed Sep 27, 2006 4:37 pm

The slower you go, the more steps it needs to make.
If the resolution of the steps is too small the servo may jitter trying to find a fractional step position it can never attain.

Ah, good point. The jittering though seems more like a pause in the actuation rather than a "search".

It is very possible that their pulse width is fluctuating.
Who knows what they are sending.

True-true. I figured that by changing the speed, it's broadens or shortens the gap between position pulses (if a pulse is indeed consistently being sent... regardless) Like w/ PTP activated, none of the servos will travel faster than the one moving in the largest range (we'll call it the "pace servo"). If a servo can only move 1 deg and have x time to do it in... if x is a long time (relative), it has to waste time by adding in dead-space so it won't end before the others.
The jittering servo is like:
1deg... wait for other servos to catch up... 1deg... wait for other servos to catch up...
while the pace servo is moving like:
1deg... 1deg... 1deg... 1deg...

Please send me an some example code that causes the problem.

For instance, If you make the arm rotate from forward pointing to backward pointing (maybe have the shoulders rotate as well) and set the speed to 1, youll see it. I'd whip ya up a code that demos it, but have to get back to work.

Talk to you soon
The slower you go, the more steps it needs to make.
If the resolution of the steps is too small the servo may jitter trying to find a fractional step position it can never attain.

Ah, good point. The jittering though seems more like a pause in the actuation rather than a "search".

It is very possible that their pulse width is fluctuating.
Who knows what they are sending.

True-true. I figured that by changing the speed, it's broadens or shortens the gap between position pulses (if a pulse is indeed consistently being sent... regardless) Like w/ PTP activated, none of the servos will travel faster than the one moving in the largest range (we'll call it the "pace servo"). If a servo can only move 1 deg and have x time to do it in... if x is a long time (relative), it has to waste time by adding in dead-space so it won't end before the others.
The jittering servo is like:
1deg... wait for other servos to catch up... 1deg... wait for other servos to catch up...
while the pace servo is moving like:
1deg... 1deg... 1deg... 1deg...

Please send me an some example code that causes the problem.

For instance, If you make the arm rotate from forward pointing to backward pointing (maybe have the shoulders rotate as well) and set the speed to 1, youll see it. I'd whip ya up a code that demos it, but have to get back to work.

Talk to you soon
bauermech
Site Admin
Site Admin
User avatar
Posts: 318
Joined: Sat Feb 04, 2006 1:00 am
Location: Defiance, Ohio, USA

Post by fnastro » Thu Sep 28, 2006 2:49 am

Post by fnastro
Thu Sep 28, 2006 2:49 am

I found some more info on Reprogramming the ATMega128. Using the HVPP Mode. This is a special programming mode for reprogramming a chip that needs the fuse bits reset. Here is a site that describes the circuit http://elm-chan.org/works/avrx/report_e.html#AVRXP. Both the STK500 and the Dragon supports HVPP.
I found some more info on Reprogramming the ATMega128. Using the HVPP Mode. This is a special programming mode for reprogramming a chip that needs the fuse bits reset. Here is a site that describes the circuit http://elm-chan.org/works/avrx/report_e.html#AVRXP. Both the STK500 and the Dragon supports HVPP.
fnastro
Robot Builder
Robot Builder
User avatar
Posts: 17
Joined: Fri Sep 15, 2006 1:00 am

Post by DanAlbert » Thu Sep 28, 2006 4:53 am

Post by DanAlbert
Thu Sep 28, 2006 4:53 am

It's a possiblility. But are all the pins for parallel programming brought out?
And are those that are not tied to anything else?

BTW.
I screwed up. I didn't read all the servo info that i-bot had posted until today.

Unlike standard RC servos the Hitec servos PWM range is more than 1 mSec.
So there is enough time at 7.3728 MHz to do 1/2 degree stepping.

I am eating crow, and loving it!
It's a possiblility. But are all the pins for parallel programming brought out?
And are those that are not tied to anything else?

BTW.
I screwed up. I didn't read all the servo info that i-bot had posted until today.

Unlike standard RC servos the Hitec servos PWM range is more than 1 mSec.
So there is enough time at 7.3728 MHz to do 1/2 degree stepping.

I am eating crow, and loving it!
DanAlbert
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 70
Joined: Fri Feb 04, 2005 1:00 am

Post by limor » Thu Sep 28, 2006 9:56 am

Post by limor
Thu Sep 28, 2006 9:56 am

fnastro wrote:I found some more info on Reprogramming the ATMega128. Using the HVPP Mode. This is a special programming mode for reprogramming a chip that needs the fuse bits reset. Here is a site that describes the circuit http://elm-chan.org/works/avrx/report_e.html#AVRXP. Both the STK500 and the Dragon supports HVPP.


This requires linking to a programmer all the 8 PD and 8 PB pins and also PA0 and Xtal. See page 293 on the Atmega128 pdf).
fnastro wrote:I found some more info on Reprogramming the ATMega128. Using the HVPP Mode. This is a special programming mode for reprogramming a chip that needs the fuse bits reset. Here is a site that describes the circuit http://elm-chan.org/works/avrx/report_e.html#AVRXP. Both the STK500 and the Dragon supports HVPP.


This requires linking to a programmer all the 8 PD and 8 PB pins and also PA0 and Xtal. See page 293 on the Atmega128 pdf).
limor
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 1845
Joined: Mon Oct 11, 2004 1:00 am
Location: London, UK

Post by DanAlbert » Thu Sep 28, 2006 2:00 pm

Post by DanAlbert
Thu Sep 28, 2006 2:00 pm

So the biggest issue is the PD5 pin that our "friends" at Hitec tied to the buzzer.

I considered building a parallel programmer until I saw that.
I doubt that a parallel programmer will work with that in the circuit.

In addition they didn't bring out PD4,6 and 7 so you would need to solder a line onto them somehow.

It is almost cheaper and easier to build a new board and trash the MR-C3024.

Unless we can get into the bootloader.


Maybe we could get a petition and send it to Tony Ohm at Hitec.
He could forward it to Hitec and just maybe they care enough about their customers and future market share to release the bootloader's secret.
So the biggest issue is the PD5 pin that our "friends" at Hitec tied to the buzzer.

I considered building a parallel programmer until I saw that.
I doubt that a parallel programmer will work with that in the circuit.

In addition they didn't bring out PD4,6 and 7 so you would need to solder a line onto them somehow.

It is almost cheaper and easier to build a new board and trash the MR-C3024.

Unless we can get into the bootloader.


Maybe we could get a petition and send it to Tony Ohm at Hitec.
He could forward it to Hitec and just maybe they care enough about their customers and future market share to release the bootloader's secret.
DanAlbert
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 70
Joined: Fri Feb 04, 2005 1:00 am

Post by limor » Thu Sep 28, 2006 11:37 pm

Post by limor
Thu Sep 28, 2006 11:37 pm

i-Bot wrote:
I now have the C3024 firmware fully dissasembled and it even reassembles to the same binary. I have only commented about 20%, but that is enough to determine to command interpreter and Code interpreter. To map the RAM and EEPROM (not much is used) is part done, but this only has relevance under Robobasic.


i-Bot, how did you get the firmware?
i-Bot wrote:
I now have the C3024 firmware fully dissasembled and it even reassembles to the same binary. I have only commented about 20%, but that is enough to determine to command interpreter and Code interpreter. To map the RAM and EEPROM (not much is used) is part done, but this only has relevance under Robobasic.


i-Bot, how did you get the firmware?
limor
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 1845
Joined: Mon Oct 11, 2004 1:00 am
Location: London, UK

Post by fnastro » Fri Sep 29, 2006 12:02 am

Post by fnastro
Fri Sep 29, 2006 12:02 am

It is a shame Hitec did not make this board more accessible. I actually really like the way it is layed out. It has most everything you need and is quite compact. I'd sign the petition!
It is a shame Hitec did not make this board more accessible. I actually really like the way it is layed out. It has most everything you need and is quite compact. I'd sign the petition!
fnastro
Robot Builder
Robot Builder
User avatar
Posts: 17
Joined: Fri Sep 15, 2006 1:00 am

Post by beermat » Fri Sep 29, 2006 12:50 am

Post by beermat
Fri Sep 29, 2006 12:50 am

Me too. This robot is DESIGNED for hacking; the same must be true for the software / controller!
Me too. This robot is DESIGNED for hacking; the same must be true for the software / controller!
beermat
Savvy Roboteer
Savvy Roboteer
User avatar
Posts: 137
Joined: Sun Jul 23, 2006 1:00 am

PreviousNext
223 postsPage 4 of 151, 2, 3, 4, 5, 6, 7 ... 15
223 postsPage 4 of 151, 2, 3, 4, 5, 6, 7 ... 15