![]() |
Re: Arduino PWM output
Quote:
|
Re: Arduino PWM output
I have a VEX Motor Module(3-wires) that our teacher had from a Vex Kit. I have the Arduino to slowly rise the PWM from 0-255 and then lower it down. What I have found is that the motor starts moving when the PWM is at around 40. I know that around 120, the motor starts slowing down and at 170, it stops completely. Once it is at 200, the motor starts again but in the opposite direction, slow at first but gets faster around 250. At 255, the motor stops completely and at 254, it starts again. Again the motor doesnt move when the PWM is between 200 and 170 and after that, it turns again in the original direction and stops at 40.
I dont know why this is happening but the duty cycle frequency was wrong, then why does it stop completely at 255? When I hook up the pwm and ground on the arduino to a regular dc motor that you would find in an electronics kit, the motor works just like how pwm should. Here is the code I ran: Code:
boolean increasing; |
Re: Arduino PWM output
Quote:
The VEX motor module has built-in deadbands at 1) the neutral, which allows a user to feed a noisy joystick signal straight to the motor and 2) the ends, which either acts as a safety, to facilitate interfacing with the VEX system (due to hardware/programming constraints etc), or it was a design decision. Hooking up this signal to a regular DC motor produces exactly that kind of behavior, not because it's how your signal "should" behave, but because it's how motors are expected to behave in response to such signals. |
Re: Arduino PWM output
Quote:
|
Re: Arduino PWM output
Use the servo library.
|
Re: Arduino PWM output
Quote:
There are multiple reasons that this could happen, both electrical and mechanical. On the electrical side, it could be an intentional design point (unlikely). It could also be that it's designed to take a different type of pulse (also unlikely). The most probable reason is an amalgam of 1) manufacturing inconsistencies and 2) a design "flaw" stemming from the circuit design (see the discussions about Victor and Jaguar signal driving; I can't do an explanation of these mechanisms justice, nor will I attempt to). On the mechanical side, it could be a damaged bearing/bushing or shaft that gunks up in one direction and offers no resistance in the other (almost like a ratchet). |
Re: Arduino PWM output
Quote:
![]() (from Arduino.cc) ...but your motor controller is expecting this: ![]() The frequency of the signal in Hz is the number of pulses per second. The reciprocal of the frequency is the period, which is the time between the rising edges of the PWM signal. For your motor controller, this should be 50 Hz, or a 20 ms (millisecond) period. According to the Arduino documentation, the analogWrite() function produces a 490 Hz PWM signal, or a 2 ms period. The duty cycle of the signal is the ratio between the pulse width and the period. For your motor controller, the pulse width is "mapped" as follows: Full Forward: 2 ms pulse / 20 ms period = 10% duty cycle. Neutral: 1.5 ms pulse / 20 ms period = 7.5% duty cycle. Full Reverse: 1 ms pulse width / 20 ms period = 5% duty cycle. As others have suggested, the Arduino servo library should be able to produce the correct signal. 180 degrees on a servo is the equivalent of "full forward" on a motor attached to the motor controller (0 degrees is full reverse, 90 is neutral, etc.) Quote:
Hope this helps... |
Re: Arduino PWM output
Quote:
|
Re: Arduino PWM output
1 Attachment(s)
I have a custom victor library for the arduino that was written for one of my projects. This takes care of the timing issues, and duty cycle issues. While the the stock servo library will work, there are things that will cause hiccups.
Edit, I have attached the files. Attachment 12807 Greg |
Re: Arduino PWM output
Quote:
|
Re: Arduino PWM output
Here is some servo code that I put together to try to run some basic robot functions. I've not tested in out for polarity yet but the ideas are correct.
#include <Servo.h> // global variables // ------------- Servo setup ------------------------------ Servo myservo_left; Servo myservo_right; int left_pwm = 10; // set up the servo connections for the Jaguar controllers int right_pwm = 9; int rate = 0; // ------- Spike relay control signals ------------------- int FWD = 1; int REV = 2; int OFF = 0; int spike_white = 0; // pin 0 for spike signal wire int spike_red = 1; // pin 1 for spike red wire void setup() { // put your setup code here, to run once: myservo_left.attach(left_pwm); myservo_right.attach(right_pwm); pinMode(spike_white, OUTPUT); pinMode(spike_red, OUTPUT); } void loop() { // Set up the default Spike(OFF); // Make stuff happen Forward(100, 1000); // move forward as a % of full speed for ms Foward(%*full speed,ms) delay(1000); Spike(FWD); Reverse(100, 1000); delay(1000); Spike(REV); Right(50, 100); delay(1000); Left(50,200); delay(1000); Spike(OFF); Right(50, 100); delay(6000); } //------------------ Subroutines --------------------------- //----------------------------------------------------------- void Forward(int rate, int duration) { int spd = rate * 500; // set speed as a % of rate myservo_left.writeMicroseconds(1500+spd); myservo_right.writeMicroseconds(1500-spd); delay(duration); myservo_left.writeMicroseconds(1500); myservo_right.writeMicroseconds(1500); } //----------------------------------------------------------- void Reverse(int rate, int duration) { int spd = rate * 500; // set speed as a % of rate myservo_left.writeMicroseconds(1500-spd); myservo_right.writeMicroseconds(1500+spd); delay(duration); myservo_left.writeMicroseconds(1500); myservo_right.writeMicroseconds(1500); } //------------------------------------------------------------ void Left(int rate, int duration) { int spd = rate * 500; // set speed as a % of rate myservo_left.writeMicroseconds(1500+spd); myservo_right.writeMicroseconds(1500+spd); delay(duration); myservo_left.writeMicroseconds(1500); myservo_right.writeMicroseconds(1500); } //------------------------------------------------------------ void Right(int rate, int duration) { int spd = rate * 500; // set speed as a % of rate myservo_left.writeMicroseconds(1500-spd); myservo_right.writeMicroseconds(1500-spd); delay(duration); myservo_left.writeMicroseconds(1500); myservo_right.writeMicroseconds(1500); } //--------------------------------------------------------------- void Spike(int state) { //states can be 0=Off, 1 = FWD, 2=REV switch (state) { case 0: digitalWrite(spike_red, LOW); digitalWrite(spike_white, LOW); break; case 1: digitalWrite(spike_red, HIGH); digitalWrite(spike_white, LOW); break; case 2: digitalWrite(spike_red, LOW); digitalWrite(spike_white, HIGH); break; default: digitalWrite(spike_red, LOW); digitalWrite(spike_white, LOW); break; } } |
Re: Arduino PWM output
to run a victor with anything besides the current FIRST robot control system or the old IFI system you need a "signal driver cable" instead of a normal PWM cable.
|
Re: Arduino PWM output
Quote:
|
Re: Arduino PWM output
Quote:
I keep reading this on here but I have personally run an old blue label victor 883 directly from a 5v arduino(pro SMD version from sparkfun). Your mileage may vary of course. |
Re: Arduino PWM output
That signal driver cable is only required to boost a standard RC receiver PWM signal to the level required by a Victor. An RC receiver normally drives servos and RC motor controllers that get by on a lower power signal.
|
| All times are GMT -5. The time now is 19:13. |
Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi