PDA

Archiv verlassen und diese Seite im Standarddesign anzeigen : RP6Control M32: Library für 8 Servos



Dirk
31.12.2008, 11:47
Hallo Leute,

nach meiner Servo-Library für die RP6Base hier:
https://www.roboternetz.de/phpBB2/viewtopic.php?t=45180
... jetzt auch eine einfache Version für max. 8 Servos für die RP6Control M32.

Demoprogramm:

// Uncommented Version of RP6ControlServo.c
// written by Dirk
// ------------------------------------------------------------------------------------------

#include "RP6ControlServoLib.h"

uint16_t pos = 0;

int main(void)
{
initRP6Control();

initLCD();

showScreenLCD("################", "################");
mSleep(1500);
showScreenLCD("<<RP6 Control>>", "<<LC - DISPLAY>>");
mSleep(2500);
showScreenLCD(" Servo - Test 1 ", " Version 1.00 ");
mSleep(2500);
clearLCD();

setLEDs(0b111111);
mSleep(500);
setLEDs(0b000000);

initSERVO(SERVO1 | SERVO2);

startStopwatch2();

while(true)
{

if (getStopwatch2() > 48) {
servo1_position = pos;
servo2_position = pos;
setCursorPosLCD(0, 0);
writeStringLCD_P("Servopos.: ");
writeIntegerLCD(pos, DEC);
writeStringLCD_P(" ");

pos++;
if (pos > RIGHT_TOUCH) {pos = 0;}
setStopwatch2(0);
}

task_SERVO();

mSleep(3);
}
return 0;
}

Header-Datei (RP6ControlServoLib.h):

/* ************************************************** **************************
* _______________________
* \| RP6 ROBOT SYSTEM |/
* \_-_-_-_-_-_-_-_-_-_/ >>> RP6 CONTROL
* ----------------------------------------------------------------------------
* ------------------------ [c]2008 - Dirk ------------------------------------
* ************************************************** **************************
* File: RP6ControlServoLib.h
* Version: 1.0
* Target: RP6 CONTROL - ATMEGA32 @16.00MHz
* Author(s): Dirk
* ************************************************** **************************
* Description:
* This is the RP6ControlServoLib header file.
* You have to include this file, if you want to use the library
* RP6ControlServoLib.c in your own projects.
*
* ************************************************** **************************
* THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
* ************************************************** **************************
*/

/************************************************** ***************************/
// Includes:

#include "RP6ControlLib.h" // The RP6 Control Library.
// Always needs to be included!

/************************************************** ***************************/
// Defines:

// Servo constants:
#define SERVO1 0b00000001
#define SERVO2 0b00000010
#define SERVO3 0b00000100
#define SERVO4 0b00001000
#define SERVO5 0b00010000
#define SERVO6 0b00100000
#define SERVO7 0b01000000
#define SERVO8 0b10000000

// Servo movement limits (depending on servo type):
// Standard servos need an impulse every 20ms (50Hz). This impulse must have
// a length of 1ms (0.7 .. 1ms) to move the servo lever to the left touch
// and a length of 2ms (2 .. 2.3ms) for moving it to the right touch. In the
// middle position the servo needs an impulse length of 1.5ms (1.3 .. 1.6ms).
// If you want to modify the following constants for a certain servo type,
// you must adapt the LEFT_TOUCH constant first (values ~70 .. 100 = ~0.7 ..
// 1ms at 100kHz) by using a servo position value (servoX_position) of zero.
// After that you have two "screws" to adjust the servo movement limits:
// First you may change the RIGHT_TOUCH constant. If you choose a higher
// value than 255, you will use 16-bit values. Higher values mean a longer
// impulse length, but longer impulses than 2.3ms do not make sense.
// Second you may alter the Timer 1 frequency constant (F_TIMER1).
// A higher frequency leads to smaller steps of the servo movement. This of
// course reduces the impulse length and may be compensated again by a higher
// RIGHT_TOUCH constant. As a possible range of Timer 1 frequency values you
// may use 50kHz (20us) .. 105.263kHz (9.5us).
// HINT: If you alter F_TIMER1, you'll have to adapt LEFT_TOUCH and
// RIGHT_TOUCH again as you can see in the following table!
// Steps -> 9.5 10 12.5 15 17.5 20 [us]
// ------------------------------------------------------------------
// LEFT_TOUCH 74 71 57 47 41 35
// RIGHT_TOUCH 169 162 129 107 92 80
// F_TIMER1 105263 100000 80000 66667 57143 50000 [Hz]
#define LEFT_TOUCH 71 // Left servo touch (~0.7ms)
#define RIGHT_TOUCH 162 // Right servo touch (~2.3ms)
#define MIDDLE_POSITION (RIGHT_TOUCH / 2) // Middle position (~1.5ms)
#define PULSE_REPETITION 17 // Pulse repetition freq. (~50Hz)
#define F_TIMER1 100000 // Timer 1 frequency (100kHz)

// Servo ports:
#define SERVO1_PULSE_ON (PORTC |= IO_PC2) // PC2
#define SERVO1_PULSE_OFF (PORTC &= ~IO_PC2)
#define SERVO2_PULSE_ON (PORTC |= IO_PC3) // PC3
#define SERVO2_PULSE_OFF (PORTC &= ~IO_PC3)
#define SERVO3_PULSE_ON (PORTC |= IO_PC4) // PC4
#define SERVO3_PULSE_OFF (PORTC &= ~IO_PC4)
#define SERVO4_PULSE_ON (PORTC |= IO_PC5) // PC5
#define SERVO4_PULSE_OFF (PORTC &= ~IO_PC5)
#define SERVO5_PULSE_ON (PORTC |= IO_PC6) // PC6
#define SERVO5_PULSE_OFF (PORTC &= ~IO_PC6)
#define SERVO6_PULSE_ON (PORTC |= IO_PC7) // PC7
#define SERVO6_PULSE_OFF (PORTC &= ~IO_PC7)
#define SERVO7_PULSE_ON (PORTD |= IO_PD5) // PD5
#define SERVO7_PULSE_OFF (PORTD &= ~IO_PD5)
#define SERVO8_PULSE_ON (PORTD |= IO_PD6) // PD6
#define SERVO8_PULSE_OFF (PORTD &= ~IO_PD6)
// -----------------------------------------------------------
// Other possible ports for connecting servos to RP6Control:
//#define SERVOx_PULSE_ON (PORTA |= ADC6) // PA6
//#define SERVOx_PULSE_OFF (PORTA &= ~ADC6)
//#define SERVOx_PULSE_ON (PORTA |= ADC7) // PA7
//#define SERVOx_PULSE_OFF (PORTA &= ~ADC7)
// -----------------------------------------------------------

/************************************************** ***************************/
// Variables:

uint16_t servo1_position; // Servo 1 position [0..RIGHT_TOUCH]
uint16_t servo2_position; // Servo 2 position [0..RIGHT_TOUCH]
uint16_t servo3_position; // Servo 3 position [0..RIGHT_TOUCH]
uint16_t servo4_position; // Servo 4 position [0..RIGHT_TOUCH]
uint16_t servo5_position; // Servo 5 position [0..RIGHT_TOUCH]
uint16_t servo6_position; // Servo 6 position [0..RIGHT_TOUCH]
uint16_t servo7_position; // Servo 7 position [0..RIGHT_TOUCH]
uint16_t servo8_position; // Servo 8 position [0..RIGHT_TOUCH]

/************************************************** ***************************/
// Functions:

void initSERVO(uint8_t servos);
void startSERVO(void);
void stopSERVO(void);
void pulseSERVO(void);
void task_SERVO(void);

/************************************************** ****************************
* Additional info
* ************************************************** **************************
* Changelog:
* - v. 1.0 (initial release) 31.12.2008 by Dirk
*
* ************************************************** **************************
*/

/************************************************** ***************************/
// EOF

Bibliothek (RP6ControlServoLib.c):

/* ************************************************** **************************
* _______________________
* \| RP6 ROBOT SYSTEM |/
* \_-_-_-_-_-_-_-_-_-_/ >>> RP6 CONTROL
* ----------------------------------------------------------------------------
* ------------------------ [c]2008 - Dirk ------------------------------------
* ************************************************** **************************
* File: RP6ControlServoLib.c
* Version: 1.0
* Target: RP6 CONTROL - ATMEGA32 @16.00MHz
* Author(s): Dirk
* ************************************************** **************************
* Description:
* This is my simple RP6 Control Servo Library for up to 8 Servos.
*
* COMMENT: It is a good idea to use a separate power supply for the servos!
*
* Servo connections:
* SERVO1 -> I/O Pin 7 (IO_PC2) SERVO5 -> I/O Pin 4 (IO_PC6)
* SERVO2 -> I/O Pin 5 (IO_PC3) SERVO6 -> I/O Pin 1 (IO_PC7)
* SERVO3 -> I/O Pin 6 (IO_PC4) SERVO7 -> I/O Pin 9 (IO_PD5)
* SERVO4 -> I/O Pin 3 (IO_PC5) SERVO8 -> I/O Pin 8 (IO_PD6)
*
* ************************************************** **************************
* ATTENTION: Stopwatch 1 is used for the servo task! Please do
* not use this stopwatch elsewhere in your program!
*
* ************************************************** **************************
* THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
* ************************************************** **************************
*/

/************************************************** ***************************/
// Includes:

#include "RP6ControlServoLib.h"

/************************************************** ***************************/
// Variables:

uint8_t usedservos;
uint8_t servo_on = FALSE;

uint16_t impulselength1 = 0;
uint16_t impulselength2 = 0;
uint16_t impulselength3 = 0;
uint16_t impulselength4 = 0;
uint16_t impulselength5 = 0;
uint16_t impulselength6 = 0;
uint16_t impulselength7 = 0;
uint16_t impulselength8 = 0;

volatile uint16_t intcounter = 0;

/************************************************** ***************************/
// Functions:

/**
* INIT SERVO
*
* Call this once before using the servo function.
* Timer 1 is configured to work in "Clear Timer On
* Compare Match Mode" (CTC). So no PWM is generated!
* The timer runs on a fixed frequency (100kHz).
*
* Input: servos -> Used servos
* Examples:
* - initSERVO(SERVO1 | SERVO2) -> Use only servos 1 and 2
* - initSERVO(SERVO1 | SERVO6) -> Use only servos 1 and 6
* - initSERVO(SERVO1 | SERVO2 | SERVO8) -> Use servos 1, 2 and 8
*
*/
void initSERVO(uint8_t servos)
{
usedservos = servos; // Save used servos
impulselength1 = 0;
impulselength2 = 0;
impulselength3 = 0;
impulselength4 = 0;
impulselength5 = 0;
impulselength6 = 0;
impulselength7 = 0;
impulselength8 = 0;
if (servos & SERVO1) {DDRC |= IO_PC2; PORTC &= ~IO_PC2;}
if (servos & SERVO2) {DDRC |= IO_PC3; PORTC &= ~IO_PC3;}
if (servos & SERVO3) {DDRC |= IO_PC4; PORTC &= ~IO_PC4;}
if (servos & SERVO4) {DDRC |= IO_PC5; PORTC &= ~IO_PC5;}
if (servos & SERVO5) {DDRC |= IO_PC6; PORTC &= ~IO_PC6;}
if (servos & SERVO6) {DDRC |= IO_PC7; PORTC &= ~IO_PC7;}
if (servos & SERVO7) {DDRD |= IO_PD5; PORTD &= ~IO_PD5;}
if (servos & SERVO8) {DDRD |= IO_PD6; PORTD &= ~IO_PD6;}
// -----------------------------------------------------------
// Other possible ports for connecting servos to RP6Control:
// if (servos & SERVOx) {DDRA |= ADC6; PORTA &= ~ADC6;}
// if (servos & SERVOx) {DDRA |= ADC7; PORTA &= ~ADC7;}
// -----------------------------------------------------------
cli();
// Timer 1: Normal port operation, mode 4 (CTC), clk/8
TCCR1A = (0 << COM1A1)
| (0 << COM1A0)
| (0 << COM1B1)
| (0 << COM1B0)
| (0 << FOC1A)
| (0 << FOC1B)
| (0 << WGM11)
| (0 << WGM10);
TCCR1B = (0 << ICNC1)
| (0 << ICES1)
| (0 << WGM13)
| (1 << WGM12)
| (0 << CS12)
| (1 << CS11)
| (0 << CS10);
OCR1A = ((F_CPU/8/F_TIMER1)-1); // 19 at 100kHz
// ------------------------------------------------------
// Possible OCR1A values (F_CPU = 16000000):
// OCR1A = 2000000 / F_TIMER1 - 1 // F_TIMER1 (Steps)
// OCR1A = 18; // 105263Hz (9.5us)
// OCR1A = 19; // 100000Hz (10us)
// OCR1A = 24; // 80000Hz (12.5us)
// OCR1A = 29; // 66667Hz (15us)
// OCR1A = 34; // 57143Hz (17.5us)
// OCR1A = 39; // 50000Hz (20us)
// ------------------------------------------------------
// Enable output compare A match interrupts:
startSERVO();
sei();
startStopwatch1(); // Needed for 20ms pulse repetition
}

/**
* START SERVO
*
* If the servo function was stopped with the
* function stopSERVO() before, it can be
* started again with this function.
*
*/
void startSERVO(void)
{
TIMSK |= (1 << OCIE1A);
servo_on = TRUE;
}

/**
* STOP SERVO
*
* The servo function uses a certain amount of the
* processor's calculating time. If the servos are
* not moving for a while, the Timer 1 interrupt
* can be stopped with this function.
*
*/
void stopSERVO(void)
{
TIMSK &= ~(1 << OCIE1A);
servo_on = FALSE;
}

/**
* PULSE SERVO
*
* This is the servo pulse generation. This function
* must be called every 20ms (pulse repetition).
*
* position = 0 : Left touch
* position = RIGHT_TOUCH : Right touch
* position = MIDDLE_POSITION : Middle position
*
* ! Please make sure in your main program, that the !
* ! servo position values (servoX_position) don't !
* ! exceed RIGHT_TOUCH!!! !
*
* COMMENT: The pulses are only started here!
* The pulses end in the Timer 1 ISR!
*
*/
void pulseSERVO(void)
{
if (servo_on) {
intcounter = RIGHT_TOUCH; // Avoid interference of Timer 1 ISR!
// (Only necessary, if pulseSERVO() is called
// from outside of this library!)
if (usedservos & SERVO1) {
SERVO1_PULSE_ON; impulselength1 = LEFT_TOUCH + servo1_position;}
if (usedservos & SERVO2) {
SERVO2_PULSE_ON; impulselength2 = LEFT_TOUCH + servo2_position;}
if (usedservos & SERVO3) {
SERVO3_PULSE_ON; impulselength3 = LEFT_TOUCH + servo3_position;}
if (usedservos & SERVO4) {
SERVO4_PULSE_ON; impulselength4 = LEFT_TOUCH + servo4_position;}
if (usedservos & SERVO5) {
SERVO5_PULSE_ON; impulselength5 = LEFT_TOUCH + servo5_position;}
if (usedservos & SERVO6) {
SERVO6_PULSE_ON; impulselength6 = LEFT_TOUCH + servo6_position;}
if (usedservos & SERVO7) {
SERVO7_PULSE_ON; impulselength7 = LEFT_TOUCH + servo7_position;}
if (usedservos & SERVO8) {
SERVO8_PULSE_ON; impulselength8 = LEFT_TOUCH + servo8_position;}
intcounter = 0;
}
}

/**
* TIMER1 ISR
*
* In this ISR the servo pulses are finished, if the
* correct pulse length of each servo is reached.
*
*/
ISR (TIMER1_COMPA_vect)
{
intcounter++;
if (intcounter == impulselength1) {SERVO1_PULSE_OFF;}
if (intcounter == impulselength2) {SERVO2_PULSE_OFF;}
if (intcounter == impulselength3) {SERVO3_PULSE_OFF;}
if (intcounter == impulselength4) {SERVO4_PULSE_OFF;}
if (intcounter == impulselength5) {SERVO5_PULSE_OFF;}
if (intcounter == impulselength6) {SERVO6_PULSE_OFF;}
if (intcounter == impulselength7) {SERVO7_PULSE_OFF;}
if (intcounter == impulselength8) {SERVO8_PULSE_OFF;}
}

/**
* SERVO TASK
*
* This is the servo task. The task performes the pulse repetition
* with the help of a stopwatch.
* At the next call of the servo task (earliest about 3ms after the
* last servo pulse generation) the compare A match interrupt will
* be disabled to reduce the interrupt load. It will be enabled
* again after the next pulseSERVO() function call.
*
*/
void task_SERVO(void)
{
if (getStopwatch1() > 2) {TIMSK &= ~(1 << OCIE1A);}
if (getStopwatch1() > PULSE_REPETITION) { // Pulse every ~20ms
pulseSERVO(); // Servo pulse generation
if (servo_on) {TIMSK |= (1 << OCIE1A);}
setStopwatch1(0);
}
}

/************************************************** ****************************
* Additional info
* ************************************************** **************************
* Changelog:
* - v. 1.0 (initial release) 31.12.2008 by Dirk
*
* ************************************************** **************************
*/

/************************************************** ***************************/
// EOF


Euch allen einen guten Rutsch! Und denkt dran: um 0.00 Uhr nicht zu früh die Korken knallen lassen! Da wird an 2008 noch eine Schaltsekunde angehängt! Das ist eine gute Chance, eigene DCF-Decoder wie z.B. diesen hier für den RP6:
https://www.roboternetz.de/phpBB2/viewtopic.php?t=34240
... 'mal auf ihre Schaltsekunden-Tauglichkeit zu überprüfen. Man kann ja danach auch noch böllern! O:)

Dirk

Christian3
07.06.2009, 19:32
Cool Danke
aber ihrgent wie sagt mein Notepad das in deiner Domo 2 Fehler sind einmal hier: initSERVO(SERVO1 | SERVO2); und task_SERVO(); liegt das an mir??
kannst du das ganze mal als zip hochladen?
lg

proevofreak
02.10.2009, 20:53
hallo, ich weiß der thread ist schon etwas älter. aber da die servo ansteuerung von dirk sicherlich die grundlage von vielen unerfahreren c programmierung ist, möchte ich kurz auf Christian3 geschildertes problem beheben.

wenn man den von dirk geposteten quellcode unverändert nimmt, kommt ja die von Christian3 geschilderte ferhlermeldung.
darum muss man meiner meinung nach im demoprogramm noch oben #include "RP6ControlServoLib.c" einfügen, damit das programm fehlerfrei kompiliert werden kann.

mfg

Dirk
02.10.2009, 21:21
Hallo proevofreak,

das ist es nicht.

Fehlermeldungen bei initSERVO(SERVO1 | SERVO2) und task_SERVO() in der Demo kommen, wenn man im makefile nicht dieses hier eingetragen hat:
SRC += $(RP6_LIB_PATH)/RP6control/RP6ControlServoLib.c

Gruß Dirk

proevofreak
03.10.2009, 20:27
danke, wieder was gelernt.

proevofreak
04.10.2009, 10:46
so, nach fast schon stundenlangem durchforsten und durchdenken von dirks servo_libs für die M32 und dem dazugehörigem demoprogramm werfen sich bei mir einige fragen auf:




intcounter = RIGHT_TOUCH;
intcounter = 0;

.....
ISR (TIMER1_COMPA_vect)
{
intcounter++;
....



was hat es mit dem intcounter auf sich?

wenn ich die Lib richtig verstehe wird intcounter jedes mal im pulse_Servo der wert von RIGHT_TOUCH (also 162) zugewiesen und danach am ende von pulse_Servo bzw. sofort danach der wert 0.
wozu wird das gemacht?







impulselength1 = LEFT_TOUCH + servo1_position;
....

ISR (TIMER1_COMPA_vect)
{
intcounter++;
if (intcounter == impulselength1) {SERVO1_PULSE_OFF;}


was geschieht genau hier?

wie ich es verstehe, wird im pulse_servo der ausgewählte servoport auf high geschaltet und gleichzeitig wird die impulselength aus der Summe LEFT_TOUCH (71) und servox_position; berechnet.
der wert von servo1_position ändert sich ja in dirks demoprogramm ständig, somit ja auch die impulselength1.
wenn ich dirks demoprogramm richtig verstehe, geht der wert von servo1_position stehts von [0...163].
somit der wert von impulselength1 von [71....234]
Richtig?

bei der ISR habe ich berechnet, dass sie alle 0,19ms ausgelöst wird.
Richtig?
Das würde bedeuten, dass im Abstand von zwei pulse_servo- aufrufen die ISR ca. 100 mal ausgeführt wird.
beginnt der intcounter++, jetzt wenn wir mal das demoprogramm zugrunde legen und nur servo1 betrachten, in der ISR bei 0 aufwärts zu zählen oder beim wert von RIGHT_TOUCH?

bei welchem wert ist intcounter==impulselength1 und somit SERVO1_PULSE_OFF?
wie lange in ms ist dann der high impulse für servo1 in diesem demoprogramm.

die restlichen teile der Lib bzw. des programms hab ich im großen und ganzen verstanden.

ich weiß das sind jetzt eine menge fragen, nur bin ich noch nicht so C und vor allem Servo erfahren und denke, dass dirks servolib sehr gut zum ansteuern meiner 5 servos an meinem roboterarm eignet.
drum will ich alles genau wissen.

danke schon mal im voraus für eure mühen.

mfg andi

Dirk
04.10.2009, 12:51
Hallo andi,

ne Menge Fragen, puh ...

1. Intcounter:
In pulseSERVO() wird ja der Impuls für jedes Servo gestartet und am Ende der Funktion intcounter = 0 gesetzt.
Damit läuft jetzt die Zeit für die Timer1-ISR: Wenn die Impulslänge der Servos erreicht ist, wird der Impuls für das jeweilige Servo in der ISR beendet.
"intcounter = RIGHT_TOUCH;" in pulseSERVO() kann man eigentlich weglassen, wenn man pulseSERVO() nur aus dieser Lib heraus aufruft. Denkbar wäre aber, dass jemand die Impulswiederholung alle 20ms nicht mit der task_SERVO() machen will, sondern eine eigene Funktion dafür schreibt. Dann kann ich nicht garantieren, dass es nicht passiert, dass die Timer1-ISR in die Funktion pulseSERVO() "einbricht" und unkontrolliert Servoimpulse beendet, obwohl die ja gerade gestartet werden sollen. Das verhindere ich mit "intcounter = RIGHT_TOUCH;", weil damit intcounter größer als impulselengthX ist, und die ISR somit nie einen Impuls beenden kann, solange pulseSERVO() läuft.
Aber wie gesagt: "intcounter = RIGHT_TOUCH;" kann man ersatzlos streichen, wenn man die Impulswiederholung nur mit task_SERVO() machen will (es schadet aber auch nicht, wenn man es drin läßt).

2. ImpulselengthX:
Ja, genau. Die Impulslänge ist immer LEFT_TOUCH + servoX_position.
Das mache ich immer so, damit ich alle meine Servos von 0 (Null am linken Anschlag) bis zu einem Maximalwert (rechter Anschlag = RIGHT_TOUCH) mit servoX_position ansteuern kann.
Vorteil: Man kann einfach beide Anschläge in der Lib einstellen, ohne dass das Hauptprogramm sich darum kümmern muss. Einfacher wäre, eine Ansteuerung von 71..234 zu erlauben und auf den Offset von LEFT_TOUCH zu verzichten. Geht natürlich auch ...

3. Timer1-ISR Frequenz:
In der Demo wird sie mit 100kHz aufgerufen. Das ist fast schon das Maximum, das mit der M32 erreichbar ist. Das heißt, alle 10us läuft die ISR ab und zählt intcounter hoch. Der wird am Ende von pulseSERVO() auf Null gesetzt, damit beginnt der Impuls. Wird die max. Impulslänge (impulselengthX) in der ISR erreicht, wird der Impuls beendet. Bei einer ISR-Frequenz von 100kHz (= 10us) braucht man einen intcounter von 70..230 für eine Impulsdauer von 0,7..2,3ms, also für den vollen Ansteuerungsbereich.
Rechnung: 70 x 10us = 0,7ms und 230 x 10us = 2,3ms.

... so, jetzt brauche ich 'nen Kaffee. O:)

Gruß Dirk

proevofreak
04.10.2009, 14:04
puh, so viele antworten O:)
ne im ernst, vielen dank dirk für so ne ausführliche und gut erklärte antwort.
ich glaube jetzt hast du mir wirklich mächtig weitergeholfen. soweit weg war ich ja dann bisher gar nicht mit meinem verständnis, nur jetzt sind mir die zusammenhänge noch wesentlich klarer geworden.

mal schauen ob ich diese woche neben dem studium mal zum programmieren komme. ich meld mich auf jeden fall wieder, sobald ich deine lib in der praxis angewendet habe.

mfg

proevofreak
07.11.2009, 17:51
so dirk, jetzt bin ich bei der programmierung meines 5-achs-armes, wo deine lib ja die hauptrolle spielt angekommen.

allerdings stehe ich vor einem ersten problem. kann es sein, dass die servoansteuerung mit deiner lib nicht korrekt funktioniert, wenn man mehrere servos gleichzeitig ansteuert?


hier mein programm:





//Servo 1 => PC2
//Servo 2 => PC3
//Servo 3=> PC4
//Servo 4=> PC5
//Servo 5=> PC6
//Reflexkoppler => PD6

uint8_t a;

void task_teil_erkannt(void)
{if (PIND & (1<<6))
{setStopwatch3(0);
a=1;
writeString_P("kein Teil erkannt\n");}

else {a=0;
writeString_P("Teil erkannt\n");
initSERVO(SERVO1);
startStopwatch3();
}
}
void task_servoansteuerung(void)
{if (a==0 && getStopwatch3() >0)
{
servo1_position = 0;
writeString_P("Greifer zu\n");
}

if (a==0 && getStopwatch3() > 2000 )
{initSERVO(SERVO3|SERVO4);
servo3_position = MIDDLE_POSITION;
servo4_position = 50;
writeString_P("Arm hoch\n");}







}

int main(void)
{
initRP6Control();
DDRD &=~ (1<<6); //Eingang für Reflexkoppler



startStopwatch2();


while(true)
{task_servoansteuerung();

task_teil_erkannt();


task_SERVO();

mSleep(3);
}
return 0;
}



wenn ein teil erkannt wird, wird der greifer geschlossen (bis dahin funktioniert das programm), allerdings sollten dann nach 2sekunden verzögerung die servos 3 und 4 den arm nach oben fahren lassen. das geschieht leider nie, obwohl im terminal "Arm hoch" angezeigt wird. der greifer soll die ganze zeit über an seinen linken anschlag takten (das funktioniert auch schon).

kannst du mir vielleicht sagen, an was das genau liegt?

danke schon mal im voraus

mfg andi

Dirk
07.11.2009, 18:11
Hallo andi,

so ganz verstehe ich dein Prog nicht.

Rein formal:
1. Mit initSERVO() must du ALLE Servos, die du angeschlossen hast, in der Main (also VOR der while(1)-Schleife!) EINMAL definieren. Wenn du also Servos an 1, 3 und 4 hast, dann steht da:
initSERVO(SERVO1 | SERVO3 | SERVO4);
In einer Funktion (und bes. in einer Schleife) hat initSERVO nichts zu suchen.

2. Wenn sich der Arm bewegen soll, müßtest du die Servopositionen für eine bestimmte Bewegung z.B. in einer Funktion (Armrunter, Armhoch, Handauf ...) zusammen fassen. Das sind dann mehrere Positionen pro Bewegung, zwischen denen je eine Pause liegt.

Gruß Dirk

proevofreak
07.11.2009, 18:23
also, das mit dem initSERVO() hatte ich schon mal im main teil. allerdings hatte ich da das problem, dass bei allen servos wo über das programm gerade keine servox_psition = ... zugewiesen wurde wegen dem initSERVO() auf den linken anschlag getaktet haben.

manche servos in meinem arm habe ich aber leider so verbaut, dass sie in der grundposition im rechten anschlag sind, d.h. sich (unerwünscht) bewegt haben, sobald ich sie in der main mit initSERVO(...) initialisiert habe.

darum wollte ich diesem problem aus dem weg gehen, in dem ich sie erst dann initialisiere, wenn sie auch gebraucht werden.

bist du dir sicher, dass man die servoinitialisierung nicht auch so machen kann, wie bei mir?

mfg

Dirk
07.11.2009, 23:08
... bist du dir sicher, dass man die servoinitialisierung nicht auch so machen kann, wie bei mir?
Ja, da bin ich 100% sicher.

Wenn du einige Servos am Anfang schon an den rechten Anschlag bringen willst, kannst du ja in Main (vor der while(1)-Schleife) diese Servos mit servoX_position = RIGHT_TOUCH auf den rechten Anschlag stellen.
Da bleiben sie dann, bis du einen anderen Wert einstellst.

Gruß Dirk

proevofreak
08.11.2009, 14:14
danke dirk, ja stimmt, das ist ne gute idee. warum bin ich da bisher noch nicht selber darauf gekommen... wenn mein arm komplett läuft stell ich ein video für dich online. bist ja dann daran nicht ganz unbeteiligt^^.

danke nochmal

Tzimovo
24.11.2009, 01:18
Hallo Dirk,

mein erster Post hier, daher erstmal Hallo und Danke ans Roboternetz :)
viele Super Ideen und Tipps hier.

Nun zu meinem Problem: Ich probiere gerade meinem brand neuen RP6 mit M32 Modul das bewegen eines Servos beizubringen.

Der Servo (Conrad Modelcraft ES-05) ist wie im Quellcode der Lib vorgeschlagen am korrekten Port auf dem M32 board angeschlossen und hat ein eigenes Akku Pack für die 4,6V Versorgungs Spannung.

Das Demo Programm von Dirk fährt den Servo aber leider nur zum Anschlag und "zuckt" dann da.
Wenn ich den Servo vorher manuell zum anderen Anschlag drehe, dann seh ich den auch tatsächlich sauber rüber takten da bleibt er dann aber wieder zuckend stehen.

Ich habe schon versucht die Timings für LEFT und RIGHT Touch zu modifizieren, leider erfolglos, als letztes habe ich noch eine ultra light Version der Demo erzeugt:

// Uncommented Version of RP6ControlServo.c
// written by Dirk
// ------------------------------------------------------------------------------------------

#include "RP6ControlServoLib.h"

int main(void)
{
initRP6Control();

setLEDs(0b111111);
mSleep(500);
setLEDs(0b000000);

/* Servo1 in die Mittlere Stellung vordefiniert */
servo1_position = RIGHT_TOUCH;

initSERVO(SERVO1);

while(true)
{
writeString("Servopos: MIDDLE \n");

servo1_position = MIDDLE_POSITION;

task_SERVO();

mSleep(500);

writeString("Servopos: LEFT \n");

servo1_position = LEFT_TOUCH;

task_SERVO();

mSleep(500);

writeString("Servopos: RIGHT \n");

servo1_position = RIGHT_TOUCH;

task_SERVO();

mSleep(500);
}
return 0;
}

Aber bei der passiert leider genau das selbe. Ich hab schon die Forum Suche beschäftigt, aber leider keinen Ansatz gefunden, warum der Servo nur in eine Richtung dreht.
Könnt Ihr mir eventuell sagen was ich da falsch mache?
Danke schon mal für die Mühe!

Uwe

proevofreak
24.11.2009, 18:03
hallo Tzimovo,
glückwunsch zum RP6 erst mal. ich habe mich mittlerweile schon öfter mit Dirks Servo Lib beschäftigt und mit hilfe ihr auch schon meinen Roboterarm angesteuert. darum hoffe ich dir helfen zu können.

bei deinem programm fallen mir einige offensichtliche fehler ein (die bei einem anfänger auch recht normal sind):

1. mSleep(500); in deiner while(true) schleife: mSleep ist eine voll blockierende zeitfunktion. d.h. dein roboter macht während der 500 ms von mSleep(500) nichts anderes mehr als zu warten. das ist besonders dann extrem nachteilig, wenn du zusätzlich zur servobewegung noch andere funktionen wie Z.b. fahren willst.
darum immer eine der Stopwatches nehmen (siehe anleitung), diese sind nämlich nicht blockierende funktionen.

2. das task_SERVO() reicht, wenn es nur einmal in der while- schleife aufgerufen wird.


damit es für dich leichter wird hier ein kurzes beispielprogramm:




#include "RP6ControlServoLib.h"





int main(void)
{
initRP6Control();



/* Servo1 in die Mittlere Stellung vordefiniert */


initSERVO(SERVO1);
servo1_position = RIGHT_TOUCH;
startStopwatch1();

while(true)
{


if (getStopwatch1() >100 && getStopwatch1() <1000)
{servo1_position = MIDDLE_POSITION;
writeString("Servopos: MIDDLE \n");}

if (getStopwatch1() > 1000 && getStopwatch1() <2000)
{servo1_position = LEFT_TOUCH;
writeString("Servopos: LEFT \n");}

if (getStopwatch1() >2000 && getStopwatch1() <3000)
{servo1_position = RIGHT_TOUCH;
writeString("Servopos: RIGHT \n");
}

if (getStopwatch1() > 3000)
{setStopwatch1(0);}

task_SERVO();
mSleep(3);
}
return 0;
}

hab das programm jetzt nicht getestet. aber so auf die art sollte es funktioneren.

mfg andi

Tzimovo
24.11.2009, 20:09
Danke für den Versuch, leider passiert mit deinem Programm exact das gleiche.
Servo zittert am Anschlag bzw. dreht vom anderen Anschlag da hin und zittert dann weiter, als ob er den Anschlag durchbrechen will. :(.
Ich habs auch mit einem zweiten baugleichen Servo probiert, leider genauso erfolglos.
Ein RS-2 Servo bewegt sich gar nicht, Ich vermute jedoch dass der mehr als die 4.8Volt des Akku Packs braucht.
Cheers,

Uwe

Dirk
24.11.2009, 20:35
Hallo Uwe,

hast du auch GND (Minuspol) des Akkupacks mit GND des RP6 verbunden?

Gruß Dirk

Tzimovo
24.11.2009, 22:02
Upps, das sollte ich nochmal ausprobieren.
Da mein haupt Rechner momentan zicken macht, werde ich mir auf meinem Laptop erstmal die Programmier Umgebung installieren.
Danke für den Hinweis!

Edit: *haut sich selbst vor den Schädel!*
Ticker ticker ticker Schnarr...
es laufen jetzt alle 3 Servos... Notitz an sich selbst: ZUMINDEST MASSE mit dem Board verbinden.

smusmut
29.01.2010, 16:27
Hallo Dirk,

Hab jetzt dein Example versucht zu kompilieren bekomme aber diese Fehlermeldung:


RP6Control_ServoTest.c:1: error: stray '\377' in program
RP6Control_ServoTest.c:1: error: stray '\376' in program
RP6Control_ServoTest.c:1:3: warning: null character(s) ignored
RP6Control_ServoTest.c:1: error: expected identifier or '(' before '/' token
RP6Control_ServoTest.c:1:6: warning: null character(s) ignored
RP6Control_ServoTest.c:1:8: warning: null character(s) ignored
RP6Control_ServoTest.c:1:12: warning: null character(s) ignored
RP6Control_ServoTest.c:1:14: warning: null character(s) ignored
RP6Control_ServoTest.c:1:16: warning: null character(s) ignored
RP6Control_ServoTest.c:1:18: warning: null character(s) ignored
RP6Control_ServoTest.c:1:20: warning: null character(s) ignored
RP6Control_ServoTest.c:1:22: warning: null character(s) ignored
RP6Control_ServoTest.c:1:24: warning: null character(s) ignored
RP6Control_ServoTest.c:1:26: warning: null character(s) ignored
RP6Control_ServoTest.c:1:28: warning: null character(s) ignored
RP6Control_ServoTest.c:1:30: warning: null character(s) ignored
RP6Control_ServoTest.c:1:32: warning: null character(s) ignored
RP6Control_ServoTest.c:1:36: warning: null character(s) ignored
RP6Control_ServoTest.c:1:38: warning: null character(s) ignored
RP6Control_ServoTest.c:1:40: warning: null character(s) ignored
RP6Control_ServoTest.c:1:42: warning: null character(s) ignored
RP6Control_ServoTest.c:1:44: warning: null character(s) ignored
RP6Control_ServoTest.c:1:46: warning: null character(s) ignored
RP6Control_ServoTest.c:1:48: warning: null character(s) ignored
RP6Control_ServoTest.c:1:52: warning: null character(s) ignored
RP6Control_ServoTest.c:1:54: warning: null character(s) ignored
RP6Control_ServoTest.c:1:58: warning: null character(s) ignored
RP6Control_ServoTest.c:1:60: warning: null character(s) ignored
RP6Control_ServoTest.c:1:62: warning: null character(s) ignored
RP6Control_ServoTest.c:1:64: warning: null character(s) ignored
RP6Control_ServoTest.c:1:66: warning: null character(s) ignored
RP6Control_ServoTest.c:1:68: warning: null character(s) ignored
RP6Control_ServoTest.c:1:70: warning: null character(s) ignored
RP6Control_ServoTest.c:1:72: warning: null character(s) ignored
RP6Control_ServoTest.c:1:74: warning: null character(s) ignored
RP6Control_ServoTest.c:1:76: warning: null character(s) ignored
RP6Control_ServoTest.c:1:78: warning: null character(s) ignored
RP6Control_ServoTest.c:1:80: warning: null character(s) ignored
RP6Control_ServoTest.c:1:82: warning: null character(s) ignored
RP6Control_ServoTest.c:1:84: warning: null character(s) ignored
RP6Control_ServoTest.c:1:86: warning: null character(s) ignored
RP6Control_ServoTest.c:1:88: warning: null character(s) ignored
RP6Control_ServoTest.c:1:90: warning: null character(s) ignored
RP6Control_ServoTest.c:2:1: warning: null character(s) ignored
RP6Control_ServoTest.c:3:1: warning: null character(s) ignored
RP6Control_ServoTest.c:3:3: warning: null character(s) ignored
RP6Control_ServoTest.c:3:5: warning: null character(s) ignored
RP6Control_ServoTest.c:3:9: warning: null character(s) ignored
RP6Control_ServoTest.c:3:11: warning: null character(s) ignored
RP6Control_ServoTest.c:3:13: warning: null character(s) ignored
RP6Control_ServoTest.c:3:15: warning: null character(s) ignored
RP6Control_ServoTest.c:3:17: warning: null character(s) ignored
RP6Control_ServoTest.c:3:19: warning: null character(s) ignored
RP6Control_ServoTest.c:3:21: warning: null character(s) ignored
RP6Control_ServoTest.c:3:25: warning: null character(s) ignored
RP6Control_ServoTest.c:3:27: warning: null character(s) ignored
RP6Control_ServoTest.c:3:31: warning: null character(s) ignored
RP6Control_ServoTest.c:3:33: warning: null character(s) ignored
RP6Control_ServoTest.c:3:35: warning: null character(s) ignored
RP6Control_ServoTest.c:3:37: warning: null character(s) ignored
RP6Control_ServoTest.c:4:1: warning: null character(s) ignored
RP6Control_ServoTest.c:5:1: warning: null character(s) ignored
RP6Control_ServoTest.c:5:3: warning: null character(s) ignored
RP6Control_ServoTest.c:5:5: warning: null character(s) ignored
RP6Control_ServoTest.c:5:9: warning: null character(s) ignored
RP6Control_ServoTest.c:5:11: warning: null character(s) ignored
RP6Control_ServoTest.c:5:13: warning: null character(s) ignored
RP6Control_ServoTest.c:5:15: warning: null character(s) ignored
RP6Control_ServoTest.c:5:17: warning: null character(s) ignored
RP6Control_ServoTest.c:5:19: warning: null character(s) ignored
RP6Control_ServoTest.c:5:21: warning: null character(s) ignored
RP6Control_ServoTest.c:5:23: warning: null character(s) ignored
RP6Control_ServoTest.c:5:25: warning: null character(s) ignored
RP6Control_ServoTest.c:5:27: warning: null character(s) ignored
RP6Control_ServoTest.c:5:29: warning: null character(s) ignored
RP6Control_ServoTest.c:5:31: warning: null character(s) ignored
RP6Control_ServoTest.c:5:33: warning: null character(s) ignored
RP6Control_ServoTest.c:5:35: warning: null character(s) ignored
RP6Control_ServoTest.c:5:37: warning: null character(s) ignored
RP6Control_ServoTest.c:5:39: warning: null character(s) ignored
RP6Control_ServoTest.c:5:41: warning: null character(s) ignored
RP6Control_ServoTest.c:5:43: warning: null character(s) ignored
RP6Control_ServoTest.c:5:45: warning: null character(s) ignored
RP6Control_ServoTest.c:5:47: warning: null character(s) ignored
RP6Control_ServoTest.c:5:49: warning: null character(s) ignored
RP6Control_ServoTest.c:5:51: warning: null character(s) ignored
RP6Control_ServoTest.c:5:53: warning: null character(s) ignored
RP6Control_ServoTest.c:5:55: warning: null character(s) ignored
RP6Control_ServoTest.c:5:57: warning: null character(s) ignored
RP6Control_ServoTest.c:5:59: warning: null character(s) ignored
RP6Control_ServoTest.c:5:61: warning: null character(s) ignored
RP6Control_ServoTest.c:5:63: warning: null character(s) ignored
RP6Control_ServoTest.c:5:65: warning: null character(s) ignored
RP6Control_ServoTest.c:5:67: warning: null character(s) ignored
RP6Control_ServoTest.c:5:69: warning: null character(s) ignored
RP6Control_ServoTest.c:5:71: warning: null character(s) ignored
RP6Control_ServoTest.c:5:73: warning: null character(s) ignored
RP6Control_ServoTest.c:5:75: warning: null character(s) ignored
RP6Control_ServoTest.c:5:77: warning: null character(s) ignored
RP6Control_ServoTest.c:5:79: warning: null character(s) ignored
RP6Control_ServoTest.c:5:81: warning: null character(s) ignored
RP6Control_ServoTest.c:5:83: warning: null character(s) ignored
RP6Control_ServoTest.c:5:85: warning: null character(s) ignored
RP6Control_ServoTest.c:5:87: warning: null character(s) ignored
RP6Control_ServoTest.c:5:89: warning: null character(s) ignored
RP6Control_ServoTest.c:5:91: warning: null character(s) ignored
RP6Control_ServoTest.c:5:93: warning: null character(s) ignored
RP6Control_ServoTest.c:5:95: warning: null character(s) ignored
RP6Control_ServoTest.c:5:97: warning: null character(s) ignored
RP6Control_ServoTest.c:5:99: warning: null character(s) ignored
... Geht dann so weiter und dann:
RP6Control_ServoTest.c:103:3: warning: null character(s) ignored
RP6Control_ServoTest.c:104:1: warning: null character(s) ignored
RP6Control_ServoTest.c:105:1: warning: null character(s) ignored
make: *** [RP6Control_ServoTest.o] Error 1

Im Makefile ist alles eingetragen.
Was mach ich falsch?

vielen Dank schonmal,
David

smusmut
30.01.2010, 17:21
Keiner eine Idee was ich machen könnte?

Dirk
30.01.2010, 17:28
Hallo smusmut,

Keiner eine Idee was ich machen könnte?
Das wahrscheinlichste ist, dass das Testprogramm beim Copy/Paste irgendwie Schaden genommen hat.

Vorschlag: Kopier es noch einmal, am besten mit dem Windows-Editor, und speichere es erst als .txt-Datei, die du dann in .c umbenennst.

Viel Erfolg.

Gruß Dirk

sputnik265
30.01.2010, 17:52
Voll perfekt! Jetzt gehts!
danke danke danke
gruß

Magelan1979
13.05.2010, 17:44
Abend, ich bin am verzweifeln.

Ich bekomme den Servo einfach nicht zum laufen.

1. Ich habe Dirk´s Lib verwendet, kompiliert, keine Fehler
2. Ich habe eine eigene Stromversorgung für den Servo
3. Ich habe die Massen verbunden
4. Ich weiß nicht mehr weiter


Die ServoPos wird brav erhöht, aber es tut sich einfach nichts. Gibt es die Möglichkeit mit Bordmitteln oder einem einfachen Multimeter zu Prüfen, ob die Signale gesendet werden?

Gruß Magelan

headnut
13.05.2010, 19:00
HI

Testen ob signale rausgehen kannst du eigentlich nur mit einem KO

Wie steurest du die Servos an?

Dirk
13.05.2010, 19:16
@Magelan1979:

Wenn du die Demo ohne Änderungen genommen hast:

1. Servo mit seiner Steuerleitung an IO_PC2 (I/O Wannenstecker Pin 7) oder an IO_PC3 (I/O Wannenstecker Pin 5) angeschlossen?

2. Keine digitalen Servos genommen, sondern "Standard-Servos"?

Gruß Dirk

Magelan1979
13.05.2010, 19:49
Meine Frau hat eben die Lösung gehabt, indem sie selber die Leitungen durchgemessen hat. Als ich gemessen habe, habe ich den Stecken immer so geknickt, dass er verbunden war. Sie hat die kalte Lötstelle entdeckt. 3 Tage fürn Arsch. Aber dennoch vielen Dank

Dirk
13.05.2010, 20:13
Meine Frau hat eben die Lösung gehabt, indem sie selber die Leitungen durchgemessen hat.
Gut, dass es Frauen gibt ... und das am Vatertag ... O:)

Gruß Dirk

inka
12.08.2010, 12:46
hi dirk,

ich habe die drei dateien vom anfang des thread im projektverzeichnis abgespeichert (ich verwende eclipse unter linux) zusammen mit

RP6Config.h
RP6Control.c +h
RP6ControlLib.c +h
RP6Uart.c +h

kompiliert, lief ohne fehlermeldung ab.
*.hex geladen...
beim start erscheint im LCD

#####
RP6 control
LC-Display
Servo-Test 1
Version 1.00

dann wird die servopos abgezählt von 1 bis 162(?)

die zwei servos sind am pin 1 und 3 des IO steckers angeschlossen..

wie gesagt, im display wird abgezählt, an den servos passiert aber nix. Hätte ich die demo.c ändern müssen?

danke

EDIT: korrektur:

wenn ich servo I an control- I/O pin 7 (PC2) anschliesse, wir der servo I nach rechts bewegt und dann schrittweise nach links

wenn ich servo II zusätzlich an pin 5 (PC3) anschliesse passiert an servo II nichts

wenn ich servo III am pin 6 (PC4) anschliesse fahren alle 3 servos auf den rechten anschlag und das programm in m32 board muss neu gestartet werden

Dirk
13.08.2010, 22:49
die zwei servos sind am pin 1 und 3 des IO steckers angeschlossen.. wie gesagt, im display wird abgezählt, an den servos passiert aber nix. Hätte ich die demo.c ändern müssen? danke
An Pin 1 und 3 von I/O wären das ja die SERVOs 6 und 4 an PC7 und PC5.
Also wäre die Initialisierung in der Demo:
initSERVO(SERVO4 | SERVO6);

wenn ich servo I an control- I/O pin 7 (PC2) anschliesse, wir der servo I nach rechts bewegt und dann schrittweise nach links
Das ist ok.

wenn ich servo II zusätzlich an pin 5 (PC3) anschliesse passiert an servo II nichts
Wenn die Demo unverändert ist, müßte das funktionieren.

wenn ich servo III am pin 6 (PC4) anschliesse fahren alle 3 servos auf den rechten anschlag und das programm in m32 board muss neu gestartet werden
Wenn du SERVO3 initialisiert hast, sollte das auch funktionieren.
Wichtig wäre eine getrennte Stromversorgung für die Servos, weil sonst evtl. die M32 immer wegen Spannungseinbrüchen ein Reset fährt.

Gruß Dirk

inka
14.08.2010, 17:30
hi Dirk,

habe jetzt die zugehörigen servos initialisiert (PC7,PC5,PC3 <-> servo 6,4,2) und habe nun ein anderes problem, bekomme beim kompilieren folgende fehlermeldung:
--------------------
Severity and Description Path Resource Location Creation Time Id
../../../../crt1/gcrt1.S undefined reference to `main' m32_control_servo_dirk line 193 1281799492208 4852
------------------

was kann das denn sein?

inka
14.08.2010, 18:26
die antwort habe ich jetzt selber: im namen der "RP6ControlServo.c" war durch copy und paste ein blank hinter dem "c", die datei wurde somit nicht als *.c erkannt.

so weit so gut, die stromversorgung der servos habe ich getrennt vom RP, einen wackler in meiner verdrahtung beseitigt.

jetzt lässt sich die datei kompilieren, beim kontaktieren der servos zu den pins PC7,PC5,PC3 (egal welches servo an welchem pin) fährt der servo zum linken anschlag (von vorne gesehen) und zuckt dann dort vor sich hin, als wollte er noch weiter.

ein fortschritt, aber ganz richtig kanns ja noch nicht sein, oder?

Magelan1979
14.08.2010, 18:41
Hast Du die Masse der externen Stromversorgung an die an des RP6 gekoppelt ? Dem sollte so sein. Steht irgendwo oben in diesem Thread

inka
15.08.2010, 13:55
jetzt habe ich die massen von RP6 und der externen servoversorgung verbunden.

servo 2 an pin 5 / PC3 tut das erwartete, auch die beiden anderen servos, wenn ich sie an diesem pin anschliesse. Am pin 3 / PC5 und pin 1 / PC7 fahren die servos an einen anschlag und bleiben dort. sie zucken auch nicht.

in der demodatei habe ich nur die initialisierung in

initSERVO(SERVO2 | SERVO4 | SERVO6);

geändert. Muss ich noch etwas ändern?

Hat es schon jemand in der praxis mit drei oder mehr servos getestet?

Ein anderes programm, mit 3 servos, allerdings mit dieser funktion
-----------------------------
for(c=0; c<50; c++)
{
PORTC |= IO_PC7; // Impulsstart servo I
sleep(12); // 1 = 0.1ms warten = Servoposition 1
PORTC &= ~IO_PC7; // Impulsende
sleep(150); //50ms warten
}
-------------------------------

funktionieren alle drei servos!

Fabian E.
15.08.2010, 14:25
Also ich benutze die Lib mit allen acht Servos ohne Probleme.
Acht gleichzeitig ist halt auch mit externer Versorgung etwas kritisch, aber prinzipiell geht es.

Dirk
15.08.2010, 14:43
Am pin 3 / PC5 und pin 1 / PC7 fahren die servos an einen anschlag und bleiben dort. sie zucken auch nicht.
Wenn du die SERVOs 2, 4, 6 benutzt, must du natürlich auch die Variablen servo2_position, servo4_position, servo6_position in der Demo verwenden, um diese Servos anzusteuern.

Es sieht so aus, als ob du servo4_position und servo6_position gar nicht änderst.

Gruß Dirk

inka
16.08.2010, 11:51
hi Dirk,

danke für den entscheidenden hinweis - es läuft!!!!

inka
17.08.2010, 12:06
hi allerseits,

ich versuche mit den drei servos ein paar positionen nacheinander anzufahren, zunächst mal zwei. mit dem code (in Dirks democode eingesetzt)


while(true)
{
servo2_position = 30;
servo4_position = 50;
servo6_position = 120;

task_SERVO();
mSleep(3);

servo2_position = 80;
servo4_position = 100;
servo6_position = 20;

task_SERVO();
mSleep(3);

}

geht es nicht. Muss ich in die while-true schleibe noch einmal zwei zählschleifen einbauen, oder wird das nacheinander abarbeiten der zwei positionen auf eine andere art erreicht?


danke...

Magelan1979
17.08.2010, 19:46
Die Positionsveränderungen der jeweiligen Servos erfolgt sehr schnell hintereinader. Versuch es mal mit einem Timer, der die jeweiligen Positione alle 2 Sek. oder so Ändert. Sollte dann funktionieren. Ist Ähnlich, als wenn Du versuchen würdest Deinen Arm alle 10 Millisekunden zu strecken, zu beugen und wieder zu strecken. Das geht einfach nicht,

Dirk
17.08.2010, 20:14
@inka:
Da gibt es einige Möglichkeiten.

Am Einfachsten:
In der while(1)-Schleife gibt es eine Stopwatch-Abfrage (a-la: if (getStopwatch2() > nnn) ...). Darin änderst du dann die 3 Servopositionen.
Das kann man z.B. so machen, dass man die Positionen in einem Array ablegt. In deinem Fall wäre das z.B. ein Array mit 3 Werten je Position. Die Größe (Zahl der Positionen) hängt von der Länge der Bewegung ab, die du machen willst.
Jedesmal, wenn die Stopwatch-Abfrage aufgerufen wird (also alle nnn ms) übergibst du die Werte aus dem Array an die Variablen servoX_position. Dann zählst du noch den Index des Array um 1 hoch.
Dadurch kannst du jede komplexe Bewegung der 3 Servos abspulen.

Wenn das alles in deinem Programm noch besser wird, gibt es mehrere Bewegungsabläufe als Funktionen in der while(1)-Schleife:

while(true)
{
task_SERVO(); // The main servo task
Bewegung1();
Bewegung2();
}

Jede Bewegung sieht so ähnlich aus:

void BewegungX(void)
{
if (getStopwatchY() > nnn) { // Change position every nnn ms
// Hole 3 Servopositionen aus dem Array
// Lege sie in 3 servoX_position ab
// Inkrementiere den Array-Index
setStopwatchY(0);
}
}


Gruß Dirk

inka
17.11.2010, 17:01
hi allerseits,

ich habe ein bischen mit dem beispielprogramm von proevofreak experimentiert und habe eine frage:


#include "RP6BaseServoLib.h"





int main(void)
{
initRobotBase();



/* Servo1 in die linke Stellung vordefiniert */


initSERVO(SERVO1/* | SERVO2*/ );


startStopwatch2();

if (getStopwatch2() < 100)
{servo1_position = 55;
// servo2_position = 180;
writeString("Servopos: 55 \n");}


while(true)
{


if (getStopwatch2() > 1000 && getStopwatch2() < 2000)
{servo1_position = 0;
writeString("Servopos: left \n");}

if (getStopwatch2() > 3000 && getStopwatch2() < 4000)
{servo1_position = RIGHT_TOUCH;
writeString("Servopos: right \n");}

if (getStopwatch2() > 5000 && getStopwatch2() < 6000)
{servo1_position = MIDDLE_POSITION;
writeString("Servopos: middl_pos \n");}

if (getStopwatch2() > 7000)
{setStopwatch2(0);}

task_SERVO();
mSleep(3);
}
return 0;
}


so, wie es ist, funktioniert es für sevo I. Wenn ich servo 2 initialisiere und in position "180" fahren lasse (ist noch for der whileschleife) tut servo 2 das, die ganze mimik fängt aber bei weiteren bewegungen von servo 1 zu zittern und wackeln. servo 2 verharrt in der zugewiesenen position...

die servos werden extern versorgt, die massen sind verbunden...

wieso das so ist - ich komme einfach nicht drauf...

TrainMen
20.11.2010, 18:30
Hallo,
also ich hab nun auch mal die 8 ServoLib von Dirk ausprobiert und bin auf einige Probleme gestossen.
1. Wie kann ich denn den Servo anpassen ? . Ich habe den Servo am linken Anschlag. Wenn ich das Demo starte, springt das Horn ein Stück nach vorn und dann lüft es ruhig zum rechten Anschlag (162) =180 Grad. Die Position 0 sind aber bei mir 20-30 Grad und nicht 0 Grad
In der Header Datei habe ich schon alles möglich versucht (wenig davon verstanden) aber ich komme nicht auf 0 Grad. Mit der Hand ist das kein Problem.
2. Ich lasse beim Start meines Programm die Servos einmalig ausrichten, um sie dann später neu zu positionieren. Die Servos summen dann die ganze Zeit leise vor sich hin und bei den Versuch mal mit der Hand zu Drehen merkt man das da ein Wiederstand ist. Wie kann ich das denn abschalten ? Also so das nach einer Neupositionierung die Servos "lose" sind.

Dirk
20.11.2010, 23:21
@TrainMen:

Die Position 0 sind aber bei mir 20-30 Grad und nicht 0 Grad
Den linken Anschlag kann man mit LEFT_TOUCH einstellen. Je kleiner man die Konstante macht, umso weiter geht der Servoarm zum linken Anschlag. Ich würde mal die Werte 65, 60, 55 ... probieren.


Wie kann ich das denn abschalten ? Also so das nach einer Neupositionierung die Servos "lose" sind.
Die Servoansteuerung kann man mit stopSERVO() anhalten.

Gruß Dirk

TrainMen
21.11.2010, 15:11
@Dirk:


LEFT_TOUCH einstellen. ......die Werte 65, 60, 55 ... probieren.

ja genau, so dachte ich es mir auch, ich war bis auf 10 runter, da passiert nichts. Wenn ich an RIGHT_TOUCH spiele merke ich das sofort, und nun ?


mit stopSERVO() anhalten.

ja hatte ich auch probiert, sie sind dann zwar "lose" aber ich kann sie dann nicht mehr aktivieren. initSERVO habe ich dann erneut versucht aber da passiert dann nichts.
mfg TrainMen

Dirk
21.11.2010, 16:33
@TrainMen:

...da passiert nichts. ..., und nun ?
Wenn du LEFT_TOUCH in der RP6ControlServoLib.h geändert hast, kompilierst du ja alles neu. Nach meiner Erfahrung wird dabei manchmal die Lib nicht neu kompiliert. Ich lösche dann immer im Projekt den Unterordner .dep und alle Dateien mit .elf, .lss, .lst, .map, .o, .sym vor dem nächsten Kompilieren der Demo. Zur Sicherheit lösche ich auch .lst und .o im RP6Lib\RP6control Verzeichnis.
Wenn es das bei dir nicht ist, dann hier noch 2 geänderte Demos. Bei Version 1 fährt das Servo umgekehrt, d.h. langsam an den linken Anschlag. Dadurch kann man es besser einstellen. In Version 2 werden die beiden Endpositionen und die Mittelstellung nacheinander angefahren. Das hilft auch etwas bei der Einstellung:

VERSION 1:
==========

/************************************************** ***************************/
// Variables:

uint16_t pos = RIGHT_TOUCH;



// ............



// ---------------------------------------------------------------------
// The demo code for positioning servos 1 and 2:
if (getStopwatch2() > 48) { // Change position every ~50ms
servo1_position = pos; // Position of servo 1
servo2_position = pos; // Position of servo 2
setCursorPosLCD(0, 0);
writeStringLCD_P("Servopos.: ");
writeIntegerLCD(pos, DEC);
writeStringLCD_P(" ");

pos--; // Next position to the left
if (pos > RIGHT_TOUCH) {pos = RIGHT_TOUCH;} // pos: RIGHT_TOUCH..0
setStopwatch2(0);
}
// ---------------------------------------------------------------------





VERSION 2:
==========

// ---------------------------------------------------------------------
// The demo code for positioning servos 1 and 2:
if (getStopwatch2() > 5000) { // Change position every ~5s
if (pos == 0) {
servo1_position = 0; // Position of servo 1
servo2_position = 0;} // Position of servo 2
if (pos == 1) {
servo1_position = MIDDLE_POSITION;
servo2_position = MIDDLE_POSITION;}
if (pos == 2) {
servo1_position = RIGHT_TOUCH;
servo2_position = RIGHT_TOUCH;}
if (pos == 3) {
servo1_position = MIDDLE_POSITION;
servo2_position = MIDDLE_POSITION;}
setCursorPosLCD(0, 0);
writeStringLCD_P("Servopos.: ");
writeIntegerLCD(servo1_position, DEC);
writeStringLCD_P(" ");

pos++;
if (pos > 3) {pos = 0;}
setStopwatch2(0);
}
// ---------------------------------------------------------------------

ich kann sie dann nicht mehr aktivieren. initSERVO habe ich dann erneut versucht aber da passiert dann nichts.
Die Servos starten wieder mit startSERVO().

Gruß Dirk

inka
21.11.2010, 17:00
hi Dirk,

wahrscheinlich steht es schon irgendwo: ist der linker anschlag (LEFT_TOUCH) auf der linken seite, wenn ich auf den servo von vorne schaue (auf die achse) oder bezieht sich das auf die sicht von hinten (auf den gehäusedeckel?

gruß & dank

Dirk
21.11.2010, 17:14
@inka:
Linker Anschlag wäre auf die Achse (auf den Hebel) geschaut der Anschlag, an den der Hebel bei Linksdrehung (Drehung gegen den Uhrzeigersinn) stößt.

Gruß Dirk

klausjuergen
21.11.2010, 18:53
Hallo,

ich versuche gerade die Programme nach zu vollziehen. Es ist das erste Mal, daß ich eine neue Lib benutze. kann mir jemand sagen, wie ich mit dem Programmers Notepad die Lib übersetzt bekomme, dh. die entspr. .lst und -o Datei erstellen kann?

Gruß

Klaus

klausjuergen
21.11.2010, 19:20
Hallo,

habe meinen Fehler gefunden, hatte eine Zeile im Makefile vergessen

Gruß

Klaus

TrainMen
22.11.2010, 13:41
@Dirk


manchmal die Lib nicht neu kompiliert

das war auch mein Verdacht und so hatte ich ja auch RIGHT_Touch verändert und bildete mir ein eine Veränderung zu sehen und war mir so sicher das sie neu eingebunden wurden.
Völliger Quatsch, ich muss mich getäuscht haben, denn genau daran lag es, nach dem löschen der Dateien, funktioniert jede Änderung und die Anschläge werden auf beiden Seiten erreicht. Danke


starten wieder mit startSERVO().

MAN... bin ich blöd
mfg TrainMen

I&amp;#9829;ROBOTIC
03.01.2011, 20:43
könnt ihr mir helfen, bei mir will ein programm nicht laufen:



#include "RP6ControlServoLib.h"

int main(void)
{
initRP6Control();
initLCD();

initSERVO(SERVO1);
startStopwatch1();
setStopwatch1(0);

while(1)
{

if (getStopwatch1() > 1000 && getStopwatch1() < 2000)
{
clearLCD();
servo1_position = MIDDLE_POSITION;
showScreenLCD(" MITTLERE ", " POSITION ");
setLEDs(0b0110);
}

if (getStopwatch1() > 2000 && getStopwatch1() < 3000)
{
clearLCD();
servo1_position = LEFT_TOUCH;
showScreenLCD(" LINKE ", " POSITION ");
setLEDs(0b1000);
}

if (getStopwatch1() > 3000 && getStopwatch1() < 4000)
{
clearLCD();
servo1_position = RIGHT_TOUCH;
showScreenLCD(" RECHTE ", " POSITION ");
setLEDs(0b0001);
}

if (getStopwatch1() > 4000)
{
setStopwatch1(0);
}

task_SERVO();
}
return 0;
}


ich hab schon imma wieda ein paar sachen verändert (das programm läuft dann auch anders, aber nie so wie es sollte)


MfG Julian

Dirk
04.01.2011, 21:54
@I♥ROBOTIC:

Sieht eigentlich gut aus.

Nur 2 Hinweise:

1. In der Servo-Lib dient LEFT_TOUCH nur zum Einstellen des linken Anschlags. Sonst braucht man das nicht mehr.
Der linke Anschlag ist einfach 0.
Also:
Anstelle von: servo1_position = LEFT_TOUCH;
... einfach: servo1_position = 0;

2. Die Stopwatch-Tests müßten so funktionieren, aber ich würde es "eindeutiger" mit Klammern machen:
Anstelle von: if (getStopwatch1() > 1000 && getStopwatch1() < 2000)
... lieber: if ((getStopwatch1() > 1000) && (getStopwatch1() < 2000))

Gruß Dirk

I&amp;#9829;ROBOTIC
04.01.2011, 23:36
hab ich gemacht aber es passiert exakt ds gleiche: Servo fährt nach links und auf dem LCD wird nichts angezeigt, hin und wieder wird das programm nach ein paar sekunden dann beendet, manchmal läuft es auch ewig

Dirk
05.01.2011, 19:09
@I♥ROBOTIC:

Oh, ich sehe ... war doch nicht so gut. Das hatte ich übersehen.

Die 3 if-Zweige laufen ja permanant in der while(1) Schleife ab. Das heißt, dass ständig das LCD gelöscht und neu beschrieben wird. Da sieht man dann nichts mehr auf dem LCD.

Ersetz mal: if (getStopwatch1() > 1000 && getStopwatch1() < 2000)
durch: if (getStopwatch1() = 1000)
... und die anderen beiden if Bedingungen auch so.

Gruß Dirk

I&amp;#9829;ROBOTIC
05.01.2011, 21:02
jetzt macht der Servo gar nichts und auf dem lcd wird ganz kurz die position angezeigt, dann wechselt die position

Video:
http://www.file-upload.net/download-3105591/CIMG0028_1.wmv.html

Dirk
05.01.2011, 21:48
Ok, das hier:

* ************************************************** **************************
* ATTENTION: Stopwatch 1 is used for the servo task! Please do
* not use this stopwatch elsewhere in your program!
*
* ************************************************** **************************

... hatte ich auch noch übersehen.

Die Stopwatch1 wird von der Lib verwendet und darf im eigenen Programm nicht benutzt werden.

Also: Nimm z.B. Stopwatch2!

Gruß Dirk

I&amp;#9829;ROBOTIC
05.01.2011, 22:21
ach j das hatte ich selber auch ganz übersehen...... ^^ Danke

Filou89
01.07.2011, 11:18
Hallo Dirk,
erstmal: dein Beitrag ist einfach toll!
Mal eine kleine Frage zu Zeile 68 der Datei RP6ControlServoLib.h.
Nach meinem Verständnis müsste das doch so sein:

#define MIDDLE_POSITION ((RIGHT_TOUCH + LEFT_TOUCH) / 2) // Middle position (~1.5ms)

denn left Touch ist ja nicht gleich null.

grüsse,
Patrick

Dirk
07.07.2011, 17:40
@Patrick,

sorry, hatte erst jetzt deinen Beitrag gelesen.

Nein, die Definition in der Lib ist ok, weil ich die Servos von 0 bis RIGHT_TOUCH ansteuere.
LEFT_TOUCH wird nur in der Lib für das einmalige Einstellen des linken Anschlags benötigt.
Im Programm braucht man dann LEFT_TOUCH nicht mehr, weil der linke Anschlag 0 ist.
MIDDLE_POSITION ist dann tatsächlich RIGHT_TOUCH / 2.

Morpheus1997
09.08.2011, 22:58
hey,
ich wollte die library für 8 servos heute ausprobieren und wollte dann einfach zunächst das demo-programm ausprobieren, da ich nach einer vernünftigen servo-ansteuerung suche!
als ich das demo-programm dann erfolgreich kompilert habe, und es dann mit nem servo ausprobieren sollte, hab ich es einfach, wie in der lib beschrieben in pin 7 gesteckt (also eig sollte es ja mit 2 servos angesteuert werden, aber ich hatte gerade nur einen parat.) als ich das programm dann gestartet hab, ist weiter nichts passiert.
als ich dann mal die anderen io-s ausprobiert habe, habe ich dann einen io gefunden, wo sich am servo überhaupt was getan hat. nämlich pc7, also pin 1!
allerdings hat sich der servo auch nicht in irgendeiner art bewegt, sondern hat einfach einen lauten ton, von sich gegeben, und der servo vibrierte einwenig.
weiter ist allerdings nix passiert -.-
Bitte helft mir! würde mich über schnelle antworten freuen!
Lieben Gruß Marcel

TrainMen
10.08.2011, 01:06
wenn Du den Servo in pin1 steckst hast du PC7 und das ist Servo 1 laut der LIB, also auch
initSERVO(SERVO1); und servo1_position = pos; benutzen.
Nun es gibt viele Töne. Ein kratzendes schnarren hatte ich bei neuen Servos auch mal, nach dem Aufschrauben fand ich dann ein Zahnrad mit abgefrästen Zähnen.
Was sagt denn das Display über die Position ? Hast Du noch andere Servos zum testen ? Hast Du eine eigene Stromversorgung für die Servos ?
MfG TrainMen

Morpheus1997
10.08.2011, 10:46
hey trainmen!
es liegt nicht am servo, denn ich habe es mit anderen servos auch schon ausprobiert, immer wieder das gleiche geräusch.
es muss wohl an etwas anderes liegen.
also ein display habe ich momentan auch gar nicht angeschlossen.
LG Marcel

TrainMen
10.08.2011, 12:38
Was passiert denn wenn Du den Servo mal von Hand drehst in Mittelstellung und dann probierst ?
MfG TrainMen

Morpheus1997
10.08.2011, 15:49
es passiert weiterhin nichts..
allerdings sind mir noch 2 sachen aufgefallen, die ich noch nicht genannt hatte.
1. wenn man das programm startet leuchten bei der base von den 6 leds die linken leds deutlich heller als die rechten! die rechten leuchten nur sehr schwach-
2. wenn man das programm startet, kann man es nicht mehr durch betätigen des start/stop-Tasters beenden!
Ist das wirklich beides normal?
MFG

TrainMen
12.08.2011, 14:22
die Frage mit der Stromversorgung hast Du nicht beantwortet!
Ich kenne Dein Programm nicht, vielleicht solltest Du es mal hier reinstellen und bist Du dir sicher alles richtig angeschlossen zu haben und auch die Servos dafür geeignet sind ?
MfG TrainMen

Morpheus1997
12.08.2011, 15:45
Hey!
Also ich habe wie bereits gesagt einfach das Demo-Programm, das Dirk auf der ersten Seite gepostet hat, genommen!

// Uncommented Version of RP6ControlServo.c
// written by Dirk
// ------------------------------------------------------------------------------------------

#include "RP6ControlServoLib.h"

uint16_t pos = 0;

int main(void)
{
initRP6Control();

initLCD();

showScreenLCD("################", "################");
mSleep(1500);
showScreenLCD("<<RP6 Control>>", "<<LC - DISPLAY>>");
mSleep(2500);
showScreenLCD(" Servo - Test 1 ", " Version 1.00 ");
mSleep(2500);
clearLCD();

setLEDs(0b111111);
mSleep(500);
setLEDs(0b000000);

initSERVO(SERVO1 | SERVO2);

startStopwatch2();

while(true)
{

if (getStopwatch2() > 48) {
servo1_position = pos;
servo2_position = pos;
setCursorPosLCD(0, 0);
writeStringLCD_P("Servopos.: ");
writeIntegerLCD(pos, DEC);
writeStringLCD_P(" ");

pos++;
if (pos > RIGHT_TOUCH) {pos = 0;}
setStopwatch2(0);
}

task_SERVO();

mSleep(3);
}
return 0;
}

Als Servos benutze ich 2x den Rs2, dann 1 mal den Es-05 und 1 mal den TG9E,
aber das ist wiegesagt bei allen Servos das gleiche Problem!


die Frage mit der Stromversorgung hast Du nicht beantwortet!

Nein, ich nehme also Stromversorgung die 5 Volt VDD vom Roboter!

LG Marcel

TrainMen
13.08.2011, 00:46
Nimm doch mal eine externe Stromversorgung und versuch es dann. Denke aber daran GND mit dem Roboter zu verbinden. Ich geh mal davon aus das Deine Stromversorgung vom RP6 zusammenbricht.
MfG TrainMen

SlyD
13.08.2011, 11:37
https://www.roboternetz.de/community/threads/46023-!!!M32-st%FCrzt-mit-Servo-ab!!!?p=441994#post441994 (https://www.roboternetz.de/community/threads/46023-%21%21%21M32-st%FCrzt-mit-Servo-ab%21%21%21?p=441994#post441994)
https://www.roboternetz.de/community/threads/49217-Mal-wieder-Servo-%28greifarm%29-sorry?p=476073&viewfull=1#post476073

Einfachste möglichkeit wäre es mit einem LC Tiefpass (die Dimensionierung natürlich an die Servos anpassen - bei mehreren entsprechend dickere Spulen und Kondensatoren oder für jeden Servo einzeln) in der Versorgungsleitung zu filtern.
Besser wäre ein zweiter 1.5A 5V Spannungsregler nur für die Servos, und am besten das mit eigenen Akkus.

MfG,
SlyD

MM2forever
08.02.2013, 18:54
Hallo Dirk,

Durch meinen Thread (https://www.roboternetz.de/community/threads/60876-Mehrere-Servos-an-Wifi-Moul-Timer?p=571017#post571017) bin ich auf deine Bibliothek verwiesen wurde. Wie kann ich sie so umaendern, dass sie mit dem WIFI-Modul M256 funktioniert?

Ich habe bisher die c und h datei ins makefile eingebunden und alles was sich auf RP6Control bezieht zu RP6M256 umgeaendert (includes und inits).

Jetzt bekomme ich beim kompillieren trotzdem Fehlermeldungen wie z.b.:



../RP6Lib/custom/RP6ControlServoLib.c:42: error: 'FALSE' undeclared here (not in a function)
../RP6Lib/custom/RP6ControlServoLib.c: In function 'initSERVO':
../RP6Lib/custom/RP6ControlServoLib.c:84: error: 'IO_PC2' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:84: error: (Each undeclared identifier is reported only once
../RP6Lib/custom/RP6ControlServoLib.c:84: error: for each function it appears in.)
../RP6Lib/custom/RP6ControlServoLib.c:85: error: 'IO_PC3' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:86: error: 'IO_PC4' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:87: error: 'IO_PC5' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:88: error: 'IO_PC6' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:89: error: 'IO_PC7' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:90: error: 'IO_PD5' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:91: error: 'IO_PD6' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c: In function 'startSERVO':
../RP6Lib/custom/RP6ControlServoLib.c:141: error: 'TIMSK' undeclared (first use in this function)
../RP6Lib/custom/RP6ControlServoLib.c:142: error: 'TRUE' undeclared (first use in this function)


... usw.

Was muss ich tun?

Dirk
08.02.2013, 20:48
Ja, ich hatte deinen Post schon gesehen.
Ich hatte keine Neuauflage der M32-Servo-Lib für die M256 geplant, weil die M256 so viele Hardware-PWM-Ausgänge hat, dass man eigentlich keine Servo-Lib braucht, die eine "Soft-PWM" macht.

Wenn du trotzdem die M32-Lib anpassen willst, gibt es diese Aufgaben:
1. Im Header:
- Im Abschnitt "Servo ports:" müßtest du die Portpins der M256 eintragen, die du auf der M256 nutzen willst. Die Bezeichnung der IO-Portpins (7. Spalte) findest du hier: http://www.rn-wissen.de/index.php/RP6v2#Port-Verwendung.
Nehmen wir an, du willst für SERVO1 den Portpin PB4 nehmen, dann müßte da stehen:
#define SERVO1_PULSE_ON (PORTB |= OC2A_PI4) // PB4
#define SERVO1_PULSE_OFF (PORTB &= ~OC2A_PI4)
Genau so machst du es mit allen 8 Ports für die Servos.

2. In der Lib (.c-Datei):
- In der Funktion initSERVO() müssen die Zeilen: if (servos & SERVOx) ... angepaßt werden: Wenn du für SERVO1 den Port PB4 festgelegt hattest, müßte die Zeile für SERVO1 so aussehen:
if (servos & SERVO1) {DDRB |= OC2A_PI4; PORTB &= ~OC2A_PI4;}
Die anderen 7 Zeilen müssen auch an die jeweiligen Portpins für Servos 2..8 angepaßt werden.

- Timer1 muss genau wie bei der M32 auf CTC Modus 4 und clk/8 konfiguriert werden. Das sind die Zeilen zwischen cli() und sei(). Du müßtest die Registerbezeichnungen der M32 und der M2560 vergleichen und an die M2560 anpassen. Ich habe gerade nicht die nötige Zeit dazu. Kleinere Änderungen sind auch in startSERVO() und stopSERVO() zu machen.

Das war's dann. Wenn du irgendwo nicht weiter kommst: Schreib hier noch mal!

MM2forever
09.02.2013, 10:31
Hi Dirk, wollte nur kurz melden dass Alles wunderbar geklappt hat!

Ich musste nur noch zusaetzlich "FALSE" und "TRUE" in "false" und "true" aendern (irgendwie gefiel das dem Compiler nicht),
dann TIMSK ueberall zu TIMSK1 machen.
Die Timerkonfiguration scheint gleich zu sein bei beiden Modulen.

Vielen Dank!

MM2forever

Dirk
10.02.2013, 16:00
@MM2forever:
Super, dass alles geklappt hat.
Würdest du evtl. die angepasste Servo-Lib für die M256 hier einstellen?
Wäre bestimmt für manchen eine Hilfe ...!

MM2forever
10.02.2013, 17:28
@MM2forever:
Super, dass alles geklappt hat.
Würdest du evtl. die angepasste Servo-Lib für die M256 hier einstellen?
Wäre bestimmt für manchen eine Hilfe ...!

Das hatte ich vor Dirk, nur leider war ich zu schnell mit meinem "Alles Super".

Ich hatte zunaechst 2 Servos an die Pins PB6/OC1B und PB5/OC1A angeschlossen. Die fuhren dann dein Demo Programm ab. Als ich heute mein Testboard ein bisschen umgeloetet habe um einen 3. Servo an PG5/OC0B anzuschliessen reagierten ALLE Servos auf einmal komisch (stottern, fuhren zufaellig vorwaerts und rueckwaerts).

Ich habe dann mal nur einen Servo genommen und abwechselnd im laufenden Betrieb zwischen den 3 Ports umgesteckt - DAS geht.
Nur wenn 3 angeschlossen sind und IMMER wenn 2 angeschlossen sind und der 3. Port (OC0B) belegt ist - spinnen die Servos.

Ich habe mal ein Amperemeter dazwischengehengt - Die Servos brauchen eigentlich nur ganz wenig (im Leerlauf) - also eine Ueberlastung meiner 1A Spannungsquelle kann eigentlich nicht vorliegen. Was soll ich tun?

Gruesse
MM2forever

Dirk
10.02.2013, 18:30
Inzwischen habe ich die Lib auch einmal auf die M256 umgeschrieben. Geändert habe ich nur die 8 Ports, und habe in der TCCR1A-Definition die Bits FOC1A und FOC1B gelöscht,- die gibt es beim 2560 nicht in TCCR1A. TCCR1C = 0 habe ich noch eingefügt.

Und: Es gibt bei mir auch Probleme:
Ich habe die 8 Portpins genommen, die an IO_PWM/T2/T3 zur Verfügung stehen.

Da sieht es so aus, dass das Servo an PE7/ICP3 gar nicht und an PE4/OC3B nur mit "Unterbrechungen" funktioniert. Alle anderen Servos laufen unauffällig.
Ich sehe mir morgen mal mit dem Oszi an, was da (nicht) läuft.

MM2forever
11.02.2013, 15:13
Das TIMSK Register hast du aber auch zu TIMSK1 gemacht? Oder zu was anderem?

Dirk
11.02.2013, 22:18
Ja, TIMSK wird zu TIMSK1.

Das klappt ja auch,- nur gibt es merkwürdige Effekte bei einzelnen Ports. Ich habe bis jetzt keine Erklärung.

MM2forever
12.02.2013, 10:02
Also ich weis nicht ob das bei der Loesungssuche hilft:

Erstmal meine Definitionen nochmal:
SERVO1: PB6/OC1B
SERVO2: PB5/OC1A
SERVO3: PG5/OC0B

Ich habe festgestellt, dass wenn ich nur einen Servo initialisiere z.B. initSERVO(SERVOx); dann passieren folgende Sachen bei diesen Konstellationen:

initSERVO(SERVO1); ->> kein Servo bewegt sich, wenn das Programm laeuft
initSERVO(SERVO2); ->> kein Servo bewegt sich, wenn das Programm laeuft

initSERVO(SERVO3); ->> SERVO1 und SERVO2 bewegen sich anfangs komisch, dann faehrt SERVO1 immer von einem Anschlag zum anderen (Obwohl mein DEMO-Programm das garnicht machen soll, sonder Servo-Positionen ueber die Terminaleingabe annehmen).

Und nun der absolute Hammer:

Wenn das Programm garnicht laeuft (Also im Disply unten >READY! steht), dann ist SERVO1 lose bewegbar, SERVO2 auch,
aber SERVO3 Blockiert am rechten Anschlag.

Drehe ich nun SERVO1 und SERVO2 auch auf rechten Anschlag und drehe SERVO3 (leicht gewaltsam) nach links und lasse dann los, wandern die beiden anderen Servos, solange sich SERVO1 zum Anschlag dreht nach links!!

Ist das nur Zufall oder wofuer spricht das?

SlyD
12.02.2013, 15:03
Ich habe mal ein Amperemeter dazwischengehengt - Die Servos brauchen eigentlich nur ganz wenig (im Leerlauf) - also eine Ueberlastung meiner 1A Spannungsquelle kann eigentlich nicht vorliegen. Was soll ich tun?

Mein Posting eins über Deinem neuen hast Du beachtet?
https://www.roboternetz.de/community/threads/40090-RP6Control-M32-Library-f%C3%BCr-8-Servos/page7?p=521561&viewfull=1#post521561
(den beiden Links folgen)

Das steht auch in der Anleitung, die Steckverbinder auf der M256 und allen sonstigen Erweiterungsmodulen sind als I/O Steckverbinder ausgelegt,
nicht für Stromversorgung vieler Servos (ein zwei gehen i.d.R.).
Servos erzeugen hochfrequente Störungen auf den Versorgungsleitungen, die Peaks die auch mal locker über 1A pro Servo gehen können siehst Du mit einem Multimeter natürlich nicht. Das zeigt nur einen Mittelwert an.

Ansonsten natürlich drauf achten das ALLE Pins korrekt initialisiert wurden / als Ausgang konfiguriert sind.

MfG,
SlyD

MM2forever
12.02.2013, 15:15
Nun, so wie ich das verstehe beziehen sich die Links darauf, wenn man direkt Strom vom Robby fuer die Servos nimmt.

Ich benutze ja eine Zusaetzliche Spannungsquelle, der Masse ich mit der des Robbys verbunden habe:
https://www.roboternetz.de/community/threads/60876-Mehrere-Servos-an-Wifi-Moul-Timer?p=570986&viewfull=1#post570986
(siehe auch Bild)

SlyD
12.02.2013, 15:33
Ah das Bild hab ich mir gar nicht genau angeschaut...

Prinzipiell schonmal gut das zu trennen.
Es kann in Deinem Fall dennoch daran liegen. Ein 9V Block ist Käse für sowas.
Die sind nicht für hohe Spitzenströme ausgelegt und haben einen sehr hohen
Innenwiderstand und recht geringe Kapazität.

Häng mal den 5V Regler ans Akkupack des RP6 (+UB) oder versorge die Servos einfach
mal direkt aus den +5V des Reglers auf dem Mainboard, nimm aber einen der
Anschlüsse der dicht am Regler ist.

MfG,
SlyD

MM2forever
12.02.2013, 15:56
Episch!!!

Oh ich koennt mich so schlagen dass ich der Meinung war das es garantiert nicht an der Spannungsversorgung liegt!!!
Es lag offensichtlich an der Spannungsversorgung

Ich habe jezt eine Batteriehalterung mit 4x1,2V Akkus genommen und direkt (ohne Wandlermodul) angeschlossen.

Die 3 Servos gehen jetzt superschnell auf Position und keiner macht mehr faxen!

===

Das loest natuerlich noch nicht Dirks Problem mit den 8, ich hab ja jetzt erst 3 getestet...

Danke SlyD!

SlyD
12.02.2013, 16:04
Wunderbar! :cool:

MM2forever
12.02.2013, 16:29
@SlyD: Ja, ich bin auch begeistert :cool:

@Dirk: Ist das bei dir vielleicht auch ein aehnliches Problem? Ich habe jetzt noch 2 weitere Servos angeschlossen an PD6/T1 und PD4/ICP1 und die laufen.

Soll ich dann die Lib hier posten bzw. vorher noch mit 8 testen? (hab blos gerade nur 5 zur Hand)

Dirk
12.02.2013, 16:48
Super, dass es bei dir funktioniert!

Stell doch deine Lib ruhig hier ein! Müßte ja jetzt alles klappen!

Ich weiss jetzt, dass ich auch ein Stromversorgungsproblem hatte. Mit getrennter Stromversorgung klappt alles! (Schreibe ich ja in der Lib auch ausdrücklich,- halte mich aber selbst beim Testen nicht dran,- zzz).

MM2forever
12.02.2013, 21:28
Hier mal die 8-Servo-Lib fuer das M256 WiFi - Modul.

Konnte es nicht lassen meinen Nick mit in den Comment-Header zu schreiben ;)

Hab auch noch die Comments an sich ein bisschen angepasst.

Alle Servos koennen also an den IO_PWM/T0/T1 - Stecker angeschlossen werden:


Stecker IO_PWM/T0/T1
_______
Vdd <-|10 9| -> Servo1
Servo6 <-| 8 7| -> Servo2
Servo7 <-| 6 5| -> Servo3
Servo8 <-| 4 3| -> Servo4
Ground <-| 2 1| -> Servo5
-------


Das ist nach belieben Veraenderbar.

Und nicht vergessen: Externe Spannungsquelle fuer die Servos & die Masse dieser Quelle mit der Masse (Ground) des Roboters Verbinden!

RP6ControlServo.c


// Uncommented Version of RP6ControlServo.c
// written by Dirk / converted to WiFi Module M256 by MM2forever
// ------------------------------------------------------------------------------------------
// https://www.roboternetz.de/community/threads/40090-RP6Control-M32-Library-f%C3%BCr-8-Servos/page9?p=571435#post571435
// ------------------------------------------------------------------------------------------

#include "RP6M256Lib.h"
#include "RP6ControlServoLib.h"

uint16_t pos = 0;
uint16_t input;


void demo(void)
{

if (getStopwatch2() > 24) {
servo1_position = pos;
servo2_position = pos;
servo3_position = pos;
setCursorPosLCD(0, 0);
writeStringLCD_P("Servopos.: ");
writeIntegerLCD(pos, DEC);
writeStringLCD_P(" ");

pos++;
if (pos > RIGHT_TOUCH) {pos = 0;}
setStopwatch2(0);
}
}


int main(void)
{
initRP6M256();

initLCD();

showScreenLCD("################", "################");
mSleep(1500);
showScreenLCD("<<RP6 Control>>", "<<LC - DISPLAY>>");
mSleep(2500);
showScreenLCD(" Servo - Test 1 ", " Version 1.00 ");
mSleep(2500);
clearLCD();

setLEDs(0b111111);
mSleep(500);
setLEDs(0b000000);

initSERVO(SERVO1 | SERVO2 | SERVO3);


startStopwatch2();

while(true)
{

demo();

task_SERVO();

mSleep(3);
}
return 0;
}


RP6ControlServoLib.c


/* ************************************************** **************************
* _______________________
* \| RP6 ROBOT SYSTEM |/
* \_-_-_-_-_-_-_-_-_-_/ >>> RP6 CONTROL
* ----------------------------------------------------------------------------
* ------------------ [c]2008/2013 - Dirk / MM2forever ------------------------
* ************************************************** **************************
* File: RP6ControlServoLib.c
* Version: 1.0
* Target: RP6 CONTROL - M256 WiFi @16.00MHz
* Author(s): Dirk, MM2forever
* https://www.roboternetz.de/community/threads/40090-RP6Control-M32-Library-f%C3%BCr-8-Servos/page9?p=571435#post571435
* ************************************************** **************************
* Description:
* This is my simple RP6 Control Servo Library for up to 8 Servos.
*
* COMMENT: It is a good idea to use a separate power supply for the servos!
*
* Servo connections:
* SERVO1 -> PB6 (Pin 9 @ IO_PWM/T0/T1) SERVO5 -> PD4 (Pin 1 @ IO_PWM/T0/T1)
* SERVO2 -> PB5 (Pin 7 @ IO_PWM/T0/T1) SERVO6 -> PK5 (Pin 8 @ IO_PWM/T0/T1)
* SERVO3 -> PG5 (Pin 5 @ IO_PWM/T0/T1) SERVO7 -> PD7 (Pin 6 @ IO_PWM/T0/T1)
* SERVO4 -> PD6 (Pin 3 @ IO_PWM/T0/T1) SERVO8 -> PB7 (Pin 4 @ IO_PWM/T0/T1)
*
* ************************************************** **************************
* ATTENTION: Stopwatch 1 is used for the servo task! Please do
* not use this stopwatch elsewhere in your program!
*
* ************************************************** **************************
* THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
* ************************************************** **************************
*/

/************************************************** ***************************/
// Includes:

#include "RP6ControlServoLib.h"

/************************************************** ***************************/
// Variables:

uint8_t usedservos;
uint8_t servo_on = false;

uint16_t impulselength1 = 0;
uint16_t impulselength2 = 0;
uint16_t impulselength3 = 0;
uint16_t impulselength4 = 0;
uint16_t impulselength5 = 0;
uint16_t impulselength6 = 0;
uint16_t impulselength7 = 0;
uint16_t impulselength8 = 0;

volatile uint16_t intcounter = 0;

/************************************************** ***************************/
// Functions:

/**
* INIT SERVO
*
* Call this once before using the servo function.
* Timer 1 is configured to work in "Clear Timer On
* Compare Match Mode" (CTC). So no PWM is generated!
* The timer runs on a fixed frequency (100kHz).
*
* Input: servos -> Used servos
* Examples:
* - initSERVO(SERVO1 | SERVO2) -> Use only servos 1 and 2
* - initSERVO(SERVO1 | SERVO6) -> Use only servos 1 and 6
* - initSERVO(SERVO1 | SERVO2 | SERVO8) -> Use servos 1, 2 and 8
*
*/
void initSERVO(uint8_t servos)
{
usedservos = servos; // Save used servos
impulselength1 = 0;
impulselength2 = 0;
impulselength3 = 0;
impulselength4 = 0;
impulselength5 = 0;
impulselength6 = 0;
impulselength7 = 0;
impulselength8 = 0;
if (servos & SERVO1) {DDRB |= OC1B_PI6; PORTB &= ~OC1B_PI6;}
if (servos & SERVO2) {DDRB |= OC1A_PI5; PORTB &= ~OC1A_PI5;}
if (servos & SERVO3) {DDRG |= IO_OC0B; PORTG &= ~IO_OC0B;}
if (servos & SERVO4) {DDRD |= IO_PD6_T1; PORTD &= ~IO_PD6_T1;}
if (servos & SERVO5) {DDRD |= IO_PD4_ICP1; PORTD &= ~IO_PD4_ICP1;}
if (servos & SERVO6) {DDRK |= IO_ADC13_PI21; PORTK &= ~IO_ADC13_PI21;}
if (servos & SERVO7) {DDRD |= IO_PD7_T2; PORTD &= ~IO_PD7_T2;}
if (servos & SERVO8) {DDRB |= OC0A_OCM_PI7; PORTB &= ~OC0A_OCM_PI7;}
// -----------------------------------------------------------
// Other possible ports for connecting servos to RP6Control:
// if (servos & SERVOx) {DDRA |= ADC6; PORTA &= ~ADC6;}
// if (servos & SERVOx) {DDRA |= ADC7; PORTA &= ~ADC7;}
// -----------------------------------------------------------
cli();
// Timer 1: Normal port operation, mode 4 (CTC), clk/8
TCCR1A = (0 << COM1A1)
| (0 << COM1A0)
| (0 << COM1B1)
| (0 << COM1B0)
// | (0 << FOC1A)
// | (0 << FOC1B)
| (0 << WGM11)
| (0 << WGM10);
TCCR1B = (0 << ICNC1)
| (0 << ICES1)
| (0 << WGM13)
| (1 << WGM12)
| (0 << CS12)
| (1 << CS11)
| (0 << CS10);
TCCR1C = 0;

OCR1A = ((F_CPU/8/F_TIMER1)-1); // 19 at 100kHz
// ------------------------------------------------------
// Possible OCR1A values (F_CPU = 16000000):
// OCR1A = 2000000 / F_TIMER1 - 1 // F_TIMER1 (Steps)
// OCR1A = 18; // 105263Hz (9.5us)
// OCR1A = 19; // 100000Hz (10us)
// OCR1A = 24; // 80000Hz (12.5us)
// OCR1A = 29; // 66667Hz (15us)
// OCR1A = 34; // 57143Hz (17.5us)
// OCR1A = 39; // 50000Hz (20us)
// ------------------------------------------------------
// Enable output compare A match interrupts:
startSERVO();
sei();
startStopwatch1(); // Needed for 20ms pulse repetition
}

/**
* START SERVO
*
* If the servo function was stopped with the
* function stopSERVO() before, it can be
* started again with this function.
*
*/
void startSERVO(void)
{
TIMSK1 |= (1 << OCIE1A);
servo_on = true;
}

/**
* STOP SERVO
*
* The servo function uses a certain amount of the
* processor's calculating time. If the servos are
* not moving for a while, the Timer 1 interrupt
* can be stopped with this function.
*
*/
void stopSERVO(void)
{
TIMSK1 &= ~(1 << OCIE1A);
servo_on = false;
}

/**
* PULSE SERVO
*
* This is the servo pulse generation. This function
* must be called every 20ms (pulse repetition).
*
* position = 0 : Left touch
* position = RIGHT_TOUCH : Right touch
* position = MIDDLE_POSITION : Middle position
*
* ! Please make sure in your main program, that the !
* ! servo position values (servoX_position) don't !
* ! exceed RIGHT_TOUCH!!! !
*
* COMMENT: The pulses are only started here!
* The pulses end in the Timer 1 ISR!
*
*/
void pulseSERVO(void)
{
if (servo_on) {
intcounter = RIGHT_TOUCH; // Avoid interference of Timer 1 ISR!
// (Only necessary, if pulseSERVO() is called
// from outside of this library!)
if (usedservos & SERVO1) {
SERVO1_PULSE_ON; impulselength1 = LEFT_TOUCH + servo1_position;}
if (usedservos & SERVO2) {
SERVO2_PULSE_ON; impulselength2 = LEFT_TOUCH + servo2_position;}
if (usedservos & SERVO3) {
SERVO3_PULSE_ON; impulselength3 = LEFT_TOUCH + servo3_position;}
if (usedservos & SERVO4) {
SERVO4_PULSE_ON; impulselength4 = LEFT_TOUCH + servo4_position;}
if (usedservos & SERVO5) {
SERVO5_PULSE_ON; impulselength5 = LEFT_TOUCH + servo5_position;}
if (usedservos & SERVO6) {
SERVO6_PULSE_ON; impulselength6 = LEFT_TOUCH + servo6_position;}
if (usedservos & SERVO7) {
SERVO7_PULSE_ON; impulselength7 = LEFT_TOUCH + servo7_position;}
if (usedservos & SERVO8) {
SERVO8_PULSE_ON; impulselength8 = LEFT_TOUCH + servo8_position;}
intcounter = 0;
}
}

/**
* TIMER1 ISR
*
* In this ISR the servo pulses are finished, if the
* correct pulse length of each servo is reached.
*
*/
ISR (TIMER1_COMPA_vect)
{
intcounter++;
if (intcounter == impulselength1) {SERVO1_PULSE_OFF;}
if (intcounter == impulselength2) {SERVO2_PULSE_OFF;}
if (intcounter == impulselength3) {SERVO3_PULSE_OFF;}
if (intcounter == impulselength4) {SERVO4_PULSE_OFF;}
if (intcounter == impulselength5) {SERVO5_PULSE_OFF;}
if (intcounter == impulselength6) {SERVO6_PULSE_OFF;}
if (intcounter == impulselength7) {SERVO7_PULSE_OFF;}
if (intcounter == impulselength8) {SERVO8_PULSE_OFF;}
}

/**
* SERVO TASK
*
* This is the servo task. The task performes the pulse repetition
* with the help of a stopwatch.
* At the next call of the servo task (earliest about 3ms after the
* last servo pulse generation) the compare A match interrupt will
* be disabled to reduce the interrupt load. It will be enabled
* again after the next pulseSERVO() function call.
*
*/
void task_SERVO(void)
{
if (getStopwatch1() > 2) {TIMSK1 &= ~(1 << OCIE1A);}
if (getStopwatch1() > PULSE_REPETITION) { // Pulse every ~20ms
pulseSERVO(); // Servo pulse generation
if (servo_on) {TIMSK1 |= (1 << OCIE1A);}
setStopwatch1(0);
}
}

/************************************************** ****************************
* Additional info
* ************************************************** **************************
* Changelog:
* - v. 1.0 (initial release) 31.12.2008 by Dirk
*
* ************************************************** **************************
*/

/************************************************** ***************************/
// EOF


RP6ControlServoLib.h


/* ************************************************** **************************
* _______________________
* \| RP6 ROBOT SYSTEM |/
* \_-_-_-_-_-_-_-_-_-_/ >>> RP6 CONTROL
* ----------------------------------------------------------------------------
* ------------------ [c]2008/2013 - Dirk / MM2forever ------------------------
* ************************************************** **************************
* File: RP6ControlServoLib.h
* Version: 1.0
* Target: RP6 CONTROL - M256 WiFi @16.00MHz
* Author(s): Dirk, MM2forever
* https://www.roboternetz.de/community/threads/40090-RP6Control-M32-Library-f%C3%BCr-8-Servos/page9?p=571435#post571435
* ************************************************** **************************
* Description:
* This is the RP6ControlServoLib header file.
* You have to include this file, if you want to use the library
* RP6ControlServoLib.c in your own projects.
*
* ************************************************** **************************
* THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
* ************************************************** **************************
*/

/************************************************** ***************************/
// Includes:

// The Control M256 Library.
#include "RP6M256Lib.h" // Always needs to be included!

/************************************************** ***************************/
// Defines:

// Servo constants:
#define SERVO1 0b00000001
#define SERVO2 0b00000010
#define SERVO3 0b00000100
#define SERVO4 0b00001000
#define SERVO5 0b00010000
#define SERVO6 0b00100000
#define SERVO7 0b01000000
#define SERVO8 0b10000000

// Servo movement limits (depending on servo type):
// Standard servos need an impulse every 20ms (50Hz). This impulse must have
// a length of 1ms (0.7 .. 1ms) to move the servo lever to the left touch
// and a length of 2ms (2 .. 2.3ms) for moving it to the right touch. In the
// middle position the servo needs an impulse length of 1.5ms (1.3 .. 1.6ms).
// If you want to modify the following constants for a certain servo type,
// you must adapt the LEFT_TOUCH constant first (values ~70 .. 100 = ~0.7 ..
// 1ms at 100kHz) by using a servo position value (servoX_position) of zero.
// After that you have two "screws" to adjust the servo movement limits:
// First you may change the RIGHT_TOUCH constant. If you choose a higher
// value than 255, you will use 16-bit values. Higher values mean a longer
// impulse length, but longer impulses than 2.3ms do not make sense.
// Second you may alter the Timer 1 frequency constant (F_TIMER1).
// A higher frequency leads to smaller steps of the servo movement. This of
// course reduces the impulse length and may be compensated again by a higher
// RIGHT_TOUCH constant. As a possible range of Timer 1 frequency values you
// may use 50kHz (20us) .. 105.263kHz (9.5us).
// HINT: If you alter F_TIMER1, you'll have to adapt LEFT_TOUCH and
// RIGHT_TOUCH again as you can see in the following table!
// Steps -> 9.5 10 12.5 15 17.5 20 [us]
// ------------------------------------------------------------------
// LEFT_TOUCH 74 71 57 47 41 35
// RIGHT_TOUCH 169 162 129 107 92 80
// F_TIMER1 105263 100000 80000 66667 57143 50000 [Hz]
#define LEFT_TOUCH 71 // Left servo touch (~0.7ms)
#define RIGHT_TOUCH 162 // Right servo touch (~2.3ms)
#define MIDDLE_POSITION (RIGHT_TOUCH / 2) // Middle position (~1.5ms)
#define PULSE_REPETITION 17 // Pulse repetition freq. (~50Hz)
#define F_TIMER1 100000 // Timer 1 frequency (100kHz)

// Servo ports:
#define SERVO1_PULSE_ON (PORTB |= OC1B_PI6) // PB6
#define SERVO1_PULSE_OFF (PORTB &= ~OC1B_PI6)
#define SERVO2_PULSE_ON (PORTB |= OC1A_PI5) // PB5
#define SERVO2_PULSE_OFF (PORTB &= ~OC1A_PI5)
#define SERVO3_PULSE_ON (PORTG |= IO_OC0B) // PG5
#define SERVO3_PULSE_OFF (PORTG &= ~IO_OC0B )
#define SERVO4_PULSE_ON (PORTD |= IO_PD6_T1)// PD6
#define SERVO4_PULSE_OFF (PORTD &= ~IO_PD6_T1)
#define SERVO5_PULSE_ON (PORTD |= IO_PD4_ICP1)//PD4
#define SERVO5_PULSE_OFF (PORTD &= ~IO_PD4_ICP1)
#define SERVO6_PULSE_ON (PORTK |= IO_ADC13_PI21)// PK5
#define SERVO6_PULSE_OFF (PORTK &= ~IO_ADC13_PI21)
#define SERVO7_PULSE_ON (PORTD |= IO_PD7_T2) // PD7
#define SERVO7_PULSE_OFF (PORTD &= ~IO_PD7_T2)
#define SERVO8_PULSE_ON (PORTB |= OC0A_OCM_PI7)// PB7
#define SERVO8_PULSE_OFF (PORTB &= ~OC0A_OCM_PI7)
// -----------------------------------------------------------
// Other possible ports for connecting servos to RP6Control:
//#define SERVOx_PULSE_ON (PORTA |= ADC6) // PA6
//#define SERVOx_PULSE_OFF (PORTA &= ~ADC6)
//#define SERVOx_PULSE_ON (PORTA |= ADC7) // PA7
//#define SERVOx_PULSE_OFF (PORTA &= ~ADC7)
// -----------------------------------------------------------

/************************************************** ***************************/
// Variables:

uint16_t servo1_position; // Servo 1 position [0..RIGHT_TOUCH]
uint16_t servo2_position; // Servo 2 position [0..RIGHT_TOUCH]
uint16_t servo3_position; // Servo 3 position [0..RIGHT_TOUCH]
uint16_t servo4_position; // Servo 4 position [0..RIGHT_TOUCH]
uint16_t servo5_position; // Servo 5 position [0..RIGHT_TOUCH]
uint16_t servo6_position; // Servo 6 position [0..RIGHT_TOUCH]
uint16_t servo7_position; // Servo 7 position [0..RIGHT_TOUCH]
uint16_t servo8_position; // Servo 8 position [0..RIGHT_TOUCH]

/************************************************** ***************************/
// Functions:

void initSERVO(uint8_t servos);
void startSERVO(void);
void stopSERVO(void);
void pulseSERVO(void);
void task_SERVO(void);

/************************************************** ****************************
* Additional info
* ************************************************** **************************
* Changelog:
* - v. 1.0 (initial release) 31.12.2008 by Dirk
*
* ************************************************** **************************
*/

/************************************************** ***************************/
// EOF

Dirk
12.02.2013, 22:17
Hier noch die Anpassungen, wenn man die Portpins am IO_PWM/T2/T3 Stecker der M256 nehmen will:

Stecker IO_PWM/T2/T3
_______
Vdd <-|10 9| -> Servo8
Servo7 <-| 8 7| -> Servo6
Servo5 <-| 6 5| -> Servo4
Servo3 <-| 4 3| -> Servo2
Ground <-| 2 1| -> Servo1
-------

********* in der Lib **********
* Servo connections at IO_PWM/T2/T3:
* SERVO1 -> Pin 1 (IO_PE7_ICP3_I7) SERVO5 -> Pin 6 (IO_ADC15_PI23)
* SERVO2 -> Pin 3 (IO_PE6_T3_I6) SERVO6 -> Pin 7 (IO_PH6_OC2B)
* SERVO3 -> Pin 4 (IO_PE5_OC3C_I5) SERVO7 -> Pin 8 (IO_ADC14_PI22)
* SERVO4 -> Pin 5 (OC2A_PI4) SERVO8 -> Pin 9 (IO_PE4_OC3B_I4)


if (servos & SERVO1) {DDRE |= IO_PE7_ICP3_I7; PORTE &= ~IO_PE7_ICP3_I7;}
if (servos & SERVO2) {DDRE |= IO_PE6_T3_I6; PORTE &= ~IO_PE6_T3_I6;}
if (servos & SERVO3) {DDRE |= IO_PE5_OC3C_I5; PORTE &= ~IO_PE5_OC3C_I5;}
if (servos & SERVO4) {DDRB |= OC2A_PI4; PORTB &= ~OC2A_PI4;}
if (servos & SERVO5) {DDRK |= IO_ADC15_PI23; PORTK &= ~IO_ADC15_PI23;}
if (servos & SERVO6) {DDRH |= IO_PH6_OC2B; PORTH &= ~IO_PH6_OC2B;}
if (servos & SERVO7) {DDRK |= IO_ADC14_PI22; PORTK &= ~IO_ADC14_PI22;}
if (servos & SERVO8) {DDRE |= IO_PE4_OC3B_I4; PORTE &= ~IO_PE4_OC3B_I4;}
// -----------------------------------------------------------
// Other possible ports for connecting servos to RP6 M256:
// At IO_PWM/T0/T1: PD4, PD6, PB7, PG5, PD7, PB5, PK5, PB6
// At UART_SPI1/T5: PL1, PL2, PD5, PL3, PD3, PL5, PD2, PL4
// At UART_SPI2/T4: PL0, PH7, PH2, PH5, PH1, PH4, PH0, PH3
// -----------------------------------------------------------


********* im Header **********
// Servo ports (at IO_PWM/T2/T3):
#define SERVO1_PULSE_ON (PORTE |= IO_PE7_ICP3_I7) // PE7
#define SERVO1_PULSE_OFF (PORTE &= ~IO_PE7_ICP3_I7)
#define SERVO2_PULSE_ON (PORTE |= IO_PE6_T3_I6) // PE6
#define SERVO2_PULSE_OFF (PORTE &= ~IO_PE6_T3_I6)
#define SERVO3_PULSE_ON (PORTE |= IO_PE5_OC3C_I5) // PE5
#define SERVO3_PULSE_OFF (PORTE &= ~IO_PE5_OC3C_I5)
#define SERVO4_PULSE_ON (PORTB |= OC2A_PI4) // PB4
#define SERVO4_PULSE_OFF (PORTB &= ~OC2A_PI4)
#define SERVO5_PULSE_ON (PORTK |= IO_ADC15_PI23) // PK7
#define SERVO5_PULSE_OFF (PORTK &= ~IO_ADC15_PI23)
#define SERVO6_PULSE_ON (PORTH |= IO_PH6_OC2B) // PH6
#define SERVO6_PULSE_OFF (PORTH &= ~IO_PH6_OC2B)
#define SERVO7_PULSE_ON (PORTK |= IO_ADC14_PI22) // PK6
#define SERVO7_PULSE_OFF (PORTK &= ~IO_ADC14_PI22)
#define SERVO8_PULSE_ON (PORTE |= IO_PE4_OC3B_I4) // PE4
#define SERVO8_PULSE_OFF (PORTE &= ~IO_PE4_OC3B_I4)
// -----------------------------------------------------------
// Other possible ports for connecting servos to RP6 M256:
// At IO_PWM/T0/T1: PD4, PD6, PB7, PG5, PD7, PB5, PK5, PB6
// At UART_SPI1/T5: PL1, PL2, PD5, PL3, PD3, PL5, PD2, PL4
// At UART_SPI2/T4: PL0, PH7, PH2, PH5, PH1, PH4, PH0, PH3
// -----------------------------------------------------------