mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-03 19:24:09 +05:30
added support for rotating servos at different speeds
This commit is contained in:
parent
eda206f68c
commit
e9810841b4
@ -265,12 +265,15 @@ void setup() {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Attach servos if used */
|
/* Attach servos if used */
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
int i;
|
int i;
|
||||||
for (i = 0; i < N_SERVOS; i++) {
|
for (i = 0; i < N_SERVOS; i++) {
|
||||||
servos[i].initServo(servoPins[i], servoInitPosition[i]);
|
servos[i].initServo(
|
||||||
}
|
servoPins[i],
|
||||||
#endif
|
stepDelay[i],
|
||||||
|
servoInitPosition[i]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Enter the main loop. Read and parse input from the serial port
|
/* Enter the main loop. Read and parse input from the serial port
|
||||||
|
@ -2,29 +2,38 @@
|
|||||||
#define SERVOS_H
|
#define SERVOS_H
|
||||||
|
|
||||||
|
|
||||||
#define N_SERVOS 1
|
#define N_SERVOS 2
|
||||||
|
|
||||||
// This delay in milliseconds determines determines the pause
|
// This delay in milliseconds determines the pause
|
||||||
// between each one degree step the servo travels. Increasing
|
// between each one degree step the servo travels. Increasing
|
||||||
// this number will make the servo sweep more slowly.
|
// this number will make the servo sweep more slowly.
|
||||||
// Decreasing this number will make the servo sweep more quickly.
|
// Decreasing this number will make the servo sweep more quickly.
|
||||||
#define SWEEP_COMMAND_INTERVAL 0 // ms
|
// Zero is the default number and will make the servos spin at
|
||||||
|
// full speed. 150 ms makes them spin very slowly.
|
||||||
|
int stepDelay [N_SERVOS] = { 0, 0 }; // ms
|
||||||
|
|
||||||
byte servoPins [N_SERVOS] = { 3 };
|
// Pins
|
||||||
byte servoInitPosition [N_SERVOS] = { 90 }; // degrees
|
byte servoPins [N_SERVOS] = { 3, 4 };
|
||||||
|
|
||||||
|
// Initial Position
|
||||||
|
byte servoInitPosition [N_SERVOS] = { 90, 90 }; // [0, 180] degrees
|
||||||
|
|
||||||
|
|
||||||
class SweepServo
|
class SweepServo
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
SweepServo();
|
SweepServo();
|
||||||
void initServo(int servoPin, int initPosition);
|
void initServo(
|
||||||
|
int servoPin,
|
||||||
|
int stepDelayMs,
|
||||||
|
int initPosition);
|
||||||
void doSweep();
|
void doSweep();
|
||||||
void setTargetPosition(int position);
|
void setTargetPosition(int position);
|
||||||
Servo getServo();
|
Servo getServo();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Servo servo;
|
Servo servo;
|
||||||
|
int stepDelayMs;
|
||||||
int currentPositionDegrees;
|
int currentPositionDegrees;
|
||||||
int targetPositionDegrees;
|
int targetPositionDegrees;
|
||||||
long lastSweepCommand;
|
long lastSweepCommand;
|
||||||
|
@ -22,9 +22,13 @@ SweepServo::SweepServo()
|
|||||||
|
|
||||||
|
|
||||||
// Init
|
// Init
|
||||||
void SweepServo::initServo(int servoPin, int initPosition)
|
void SweepServo::initServo(
|
||||||
|
int servoPin,
|
||||||
|
int stepDelayMs,
|
||||||
|
int initPosition)
|
||||||
{
|
{
|
||||||
this->servo.attach(servoPin);
|
this->servo.attach(servoPin);
|
||||||
|
this->stepDelayMs = stepDelayMs;
|
||||||
this->currentPositionDegrees = initPosition;
|
this->currentPositionDegrees = initPosition;
|
||||||
this->targetPositionDegrees = initPosition;
|
this->targetPositionDegrees = initPosition;
|
||||||
this->lastSweepCommand = millis();
|
this->lastSweepCommand = millis();
|
||||||
@ -39,7 +43,7 @@ void SweepServo::doSweep()
|
|||||||
int delta = millis() - this->lastSweepCommand;
|
int delta = millis() - this->lastSweepCommand;
|
||||||
|
|
||||||
// Check if time for a step
|
// Check if time for a step
|
||||||
if (delta > SWEEP_COMMAND_INTERVAL) {
|
if (delta > this->stepDelayMs) {
|
||||||
// Check step direction
|
// Check step direction
|
||||||
if (this->targetPositionDegrees > this->currentPositionDegrees) {
|
if (this->targetPositionDegrees > this->currentPositionDegrees) {
|
||||||
this->currentPositionDegrees++;
|
this->currentPositionDegrees++;
|
||||||
|
Loading…
x
Reference in New Issue
Block a user