|
|
View previous topic :: View next topic |
Author |
Message |
Guest
|
SERVOS.C Problem |
Posted: Fri Jan 06, 2006 9:02 am |
|
|
Hi,
I am using the servo.c driver on my 2 wheeled robot. The chip is a PIC18F452 running at 10Mhz.
I can't get thed driver to work correctly with the motors. No matter what spinning direction I choose or what TIMER_1_DIV I set, the servos are always spinning in the same direction.
I am sure this is a timing problem. Has any of you come acros this problem?
Here is a little test program I wrote
Code: | while(1)
{
delay_ms(1000);
set_servo(RIGHT_SERVO, FORWARD, 1);
delay_ms(2000);
stop_servos();
delay_ms(1000);
set_servo(RIGHT_SERVO, BACKWARD, 1);
delay_ms(2000);
stop_servos();
delay_ms(1000);
set_servo(LEFT_SERVO, FORWARD, 1);
delay_ms(2000);
stop_servos();
delay_ms(1000);
set_servo(LEFT_SERVO, BACKWARD, 1);
delay_ms(2000);
stop_servos();
} |
The 2 servos are always spinning in the same direction. |
|
|
Guest
|
Need a little info |
Posted: Fri Jan 06, 2006 5:16 pm |
|
|
Hi,
What do the stop servo & set servo routines look like? |
|
|
gael
Joined: 08 Jan 2005 Posts: 7
|
Entire servos.c file |
Posted: Fri Jan 06, 2006 8:15 pm |
|
|
I posted the initial question. Here is the servo.c file:
Code: |
///////////////////////////////////////////////////////////////////////////
//// Library for the servo motors on the Picrobot ////
//// ////
//// ////
//// * Note: This driver uses timer one to control pulses. Edit the ////
//// line "#define TIMER_1_DIV" to configure timer one ////
//// division. ////
//// ////
//// init_servos() ////
//// Call before the set_servo() function is used ////
//// ////
//// void set_servo(int1 side, int1 direction, int8 speed) ////
//// Call to set the speed and direction of a servo ////
//// Inputs: ////
//// 1) LEFT or RIGHT ////
//// 2) FORWARD or BACKWARD ////
//// 3) 0-4 for a speed. 0 is halt in either direction. ////
//// ////
//// void stop_servos() ////
//// Call to stop both servos from turning ////
//// ////
//// void pause_servos() ////
//// Call to stop the servos and remember their speed setting ////
//// ////
//// void resume_servos() ////
//// Call to resume movement after a pause ////
//// ////
//// The main program may define LEFT_SERVO_PIN and RIGHT_SERVO_PIN ////
//// to override the defaults below. ////
//// ////
///////////////////////////////////////////////////////////////////////////
//// (C) Copyright 1996, 2003 Custom Computer Services ////
//// This source code may only be used by licensed users of the CCS C ////
//// compiler. This source code may only be distributed to other ////
//// licensed users of the CCS C compiler. No other use, reproduction ////
//// or distribution is permitted without written permission. ////
//// Derivative programs created using this software in object code ////
//// form are not restricted in any way. ////
///////////////////////////////////////////////////////////////////////////
#ifndef LEFT_SERVO_PIN
#define LEFT_SERVO_PIN PIN_D6
#define RIGHT_SERVO_PIN PIN_D7
#endif
///////////////////////////////////////////////////////////////////////////
//// Configure the timer one division setting
///////////////////////////////////////////////////////////////////////////
#ifndef TIMER_1_DIV
#define TIMER_1_DIV 2 // Number of divisions for timer 1
#endif
///////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////
//// The following may be configured to control the pulse width timing
//// All time units are seconds
///////////////////////////////////////////////////////////////////////////
#define SHORT_TIME 0.0009 // Shortest pulse width high time
#define CENTER_TIME 0.0015 // The high time for center
#define LONG_TIME 0.0021 // Longest pulse width high time
#define PULSE_TIME 0.0200 // The total time for the pulse
///////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////
#define LEFT 0
#define RIGHT 1
#define FORWARD 0
#define BACKWARD 1
///////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////
//// Uncomment to allow the stop pulse to be generated for
//// calibrating the servos. Comment this line again after
//// calibrate to ensure the servos stop when requested.
///////////////////////////////////////////////////////////////////////////
//// #define CALIBRATE_SERVOS
///////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////
#ifndef TIMER_RATE
#define TIMER_RATE getenv("CLOCK") / 4 / TIMER_1_DIV
#endif
#define SHORT_TICKS (int16)((float)TIMER_RATE * SHORT_TIME)
#define CENTER_TICKS (int16)((float)TIMER_RATE * CENTER_TIME)
#define LONG_TICKS (int16)((float)TIMER_RATE * LONG_TIME)
#define LOW_TICKS (int16)(((float)TIMER_RATE * (PULSE_TIME - CENTER_TIME)) - 42)
#define PULSE_CHANGE (int16)(LONG_TICKS - CENTER_TICKS)
const signed int16 servo_speeds[] = {0,
PULSE_CHANGE / 15,
PULSE_CHANGE / 4,
PULSE_CHANGE / 3,
PULSE_CHANGE};
signed int16 right_adjust;
signed int16 left_adjust;
int1 stop_right_servo = TRUE;
int1 stop_left_servo = TRUE;
void stop_servos();
///////////////////////////////////////////////////////////////////////////
// Purpose: Initializes timer1, enables necessary interrupts,
// and sets the servos to halt.
// This must be called before set_servo()
void init_servos()
{
#if TIMER_1_DIV == 1
setup_timer_1(T1_DIV_BY_1 | T1_INTERNAL);
#elif TIMER_1_DIV == 2
setup_timer_1(T1_DIV_BY_2 | T1_INTERNAL);
#elif TIMER_1_DIV == 4
setup_timer_1(T1_DIV_BY_4 | T1_INTERNAL);
#elif TIMER_1_DIV == 8
setup_timer_1(T1_DIV_BY_8 | T1_INTERNAL);
#endif
setup_ccp1(CCP_COMPARE_INT);
setup_ccp2(CCP_COMPARE_INT);
stop_servos();
#ifdef CALIBRATE_SERVOS
stop_right_servo = FALSE;
stop_left_servo = FALSE;
#endif
enable_interrupts(INT_CCP1);
enable_interrupts(INT_CCP2);
enable_interrupts(GLOBAL);
}
// Purpose: Control the direction and speed of a servo
// Inputs: 1) 0 for left side, 1 for right side
// 2) 0 for forward, 1 for backward
// 3) 0-4 for a speed setting
// Speeds can be configured in the lookup table.
void set_servo(int1 side, int1 direction, int8 speed)
{
if(speed < sizeof(servo_speeds)/2)
{
if(side)
{
if(speed == 0)
stop_right_servo = TRUE;
else
stop_right_servo = FALSE;
right_adjust = -servo_speeds[speed];
if(direction)
right_adjust = -right_adjust;
}
else
{
if(speed == 0)
stop_left_servo = TRUE;
else
stop_left_servo = FALSE;
left_adjust = servo_speeds[speed];
if(direction)
left_adjust = -left_adjust;
}
}
}
// Purpose: Stop the servos from moving
void stop_servos()
{
right_adjust = 0;
left_adjust = 0;
stop_right_servo = TRUE;
stop_left_servo = TRUE;
}
// Purpose: Stop the servos from moving,
// but remember their speed settings
void pause_servos()
{
stop_right_servo = TRUE;
stop_left_servo = TRUE;
}
// Purpose: Resume the servos after a pause
void resume_servos()
{
stop_right_servo = FALSE;
stop_left_servo = FALSE;
}
// Purpose: Interrupt sevice routine for ccp1 is used to control the left servo
#int_ccp1
void isr_ccp1()
{
static int1 TOGGLE_LEFT = 0;
if(stop_left_servo == FALSE)
{
if(TOGGLE_LEFT)
{
output_low(LEFT_SERVO_PIN); // Set the servo control pin to low
CCP_1 += LOW_TICKS - left_adjust; // Set CCP1 to interrupt for next high pulse
TOGGLE_LEFT = 0;
}
else
{
output_high(LEFT_SERVO_PIN); // Set the servo control pin to high
CCP_1 += CENTER_TICKS + left_adjust;// Set CCP1 to interrupt for next low pulse
TOGGLE_LEFT = 1;
}
}
}
// Purpose: Interrupt sevice routine for ccp2 is used to control the right servo
#int_ccp2
void isr_ccp2()
{
static int1 TOGGLE_RIGHT = 0;
if(stop_right_servo == FALSE)
{
if(TOGGLE_RIGHT)
{
output_low(RIGHT_SERVO_PIN);
CCP_2 += LOW_TICKS - right_adjust;
TOGGLE_RIGHT = 0;
}
else
{
output_high(RIGHT_SERVO_PIN);
CCP_2 += CENTER_TICKS + right_adjust;
TOGGLE_RIGHT = 1;
}
}
}
|
|
|
|
Guest
|
|
Posted: Sat Jan 07, 2006 7:40 am |
|
|
Hi,
That looks ok.
What kind of motors are you driving? Are they dc motors (hence H-bridge) or RC servos (3 wires, power, 0v and control).
Do you have access to an oscilloscope? Check that you are getting some PWM signals on the pins D6 and D7.
Also, try using "LEFT" instead of "LEFT_SERVO", and "RIGHT" instead of "RIGHT_SERVO" as defined in the servo.c file. I don't know where you have defined the left and right_servo words.
Se what you get, I hope that helps. |
|
|
Guest
|
|
Posted: Sat Jan 07, 2006 9:21 am |
|
|
Anonymous wrote: |
What kind of motors are you driving? Are they dc motors (hence H-bridge) or RC servos (3 wires, power, 0v and control).
|
I am using RC servos.
Anonymous wrote: |
Do you have access to an oscilloscope? Check that you are getting some PWM signals on the pins D6 and D7.
|
I dont have access to a scope, but I know that I am getting the signals on my output pins because the servos are spinning. (even though they are not spinning exactly in the intended direction.
Anonymous wrote: |
Also, try using "LEFT" instead of "LEFT_SERVO", and "RIGHT" instead of "RIGHT_SERVO" as defined in the servo.c file. I don't know where you have defined the left and right_servo words.
|
In my application, I changed all references of LEFT and RIGHT to LEFT_SERVO and RIGHT_SERVO.
The file I posted is the original servos.c version. |
|
|
Guest
|
|
Posted: Sat Jan 07, 2006 9:59 am |
|
|
Do you realise how RC servos 'work', when used like this? A RC servo, will not automatically 'stop', if fed a 1.5mSec pulse. It will only do so, if the feedback pot (which is disconnected from the mechanical drive), is set to exactly the centre position. The movement for the other pulse widths is also dependant on the position of this pot. I'd suspect that you have either completely removed the pot (in which case the servos will seek continuously in one direction, no matter what pulse is fed to them), or it is set to one end of it's travel (which will have a similar effect on most servos).
You should write a much simpler program, that just outputs a fixed 1.5mSec pulse, and adjust the pot till the servo stops with this. Only once they are 'set up' like this, then try the code you are using.
Best Wishes |
|
|
Guest
|
|
Posted: Sat Jan 07, 2006 10:16 am |
|
|
Hi,
I inclined to agree with the last reply.
You mention that the servos are "spinning" twice. I assume you are using the servos to drive wheels instead of positioning some link between 0-~180 degrees.
The servos will stop if used in positioning mode. If you apply 50% duty (perfect square wave with off-time and on-times being equal), then the servo will position itself somewhere in the middle of its positioning range.
In speed mode (no feedback potentiometer) it will never reach a target position and will continue to run in one direction. There are website showing how to modify and RC servo for speed mode.
I'm not sure if the mod will give you both speed and direction control.
Here is a site that may help:
http://www.seattlerobotics.org/guide/servohack.html
Google "modify servo" and there should be more links.
Hope it helps. |
|
|
gael
Joined: 08 Jan 2005 Posts: 7
|
|
Posted: Mon Jan 09, 2006 11:08 am |
|
|
Anonymous wrote: | Do you realise how RC servos 'work', when used like this? A RC servo, will not automatically 'stop', if fed a 1.5mSec pulse. It will only do so, if the feedback pot (which is disconnected from the mechanical drive), is set to exactly the centre position. The movement for the other pulse widths is also dependant on the position of this pot. I'd suspect that you have either completely removed the pot (in which case the servos will seek continuously in one direction, no matter what pulse is fed to them), or it is set to one end of it's travel (which will have a similar effect on most servos).
You should write a much simpler program, that just outputs a fixed 1.5mSec pulse, and adjust the pot till the servo stops with this. Only once they are 'set up' like this, then try the code you are using.
Best Wishes |
My servos are already ajusted so that a 1.5ms pulse places the servo in its centre position. After you reply, I manually made sure it was, but I am sure it was already the case.
The only mod I made to the servo was on the output shaft gear. I did not replace the pot with a couple of fixed resistors, because I want to be able to control the speed of the servo. Doing so would force the servo to spin at full speed only (in either direction).
Am I overlooking something? |
|
|
Ttelmah Guest
|
|
Posted: Mon Jan 09, 2006 11:26 am |
|
|
What is your clock rate?.
If you look at (say) the statement to calculate the 'ticks' needed for the longest pulse, this will only work, if the clock is below:
65535/(0.0021*8). 3.9MHz
Otherwise the counter value will be incorrectly calculated, resulting in an overflow.
You can handle higher clocks, by increasing the divider used on the timer.
As a comment, you are ging to be very likely to find the motor does not stop on 1.5mSec reliably. This is down to the 'deadband' setting of the servo amp, and on some chips, it is tiny.
Best Wishes |
|
|
gael
Joined: 08 Jan 2005 Posts: 7
|
|
Posted: Mon Jan 09, 2006 1:11 pm |
|
|
Thanks a lot for your help. I finally found what the problem was. It was the potentiometer. I modified it so that I can ajust its value using a screwdriver from the outside. Now, the servos seem to be working fine.
The PIC is running at 10 Mhz. I think a timer div of 4 should do fine. |
|
|
|
|
You cannot post new topics in this forum You cannot reply to topics in this forum You cannot edit your posts in this forum You cannot delete your posts in this forum You cannot vote in polls in this forum
|
Powered by phpBB © 2001, 2005 phpBB Group
|