Skip to content

Commit 6c3267a

Browse files
authored
Merge pull request #54 from sparkfun/Servo
Servo library
2 parents a83f784 + dd2eee4 commit 6c3267a

File tree

14 files changed

+670
-5
lines changed

14 files changed

+670
-5
lines changed

cores/arduino/ard_sup/analog/ap3_analog.cpp

+22-3
Original file line numberDiff line numberDiff line change
@@ -242,9 +242,15 @@ bool power_adc_disable()
242242

243243
//Apollo3 is capapble of 14-bit ADC but Arduino defaults to 10-bit
244244
//This modifies the global var that controls what is returned from analogRead()
245-
void analogReadResolution(uint8_t bits)
245+
ap3_err_t analogReadResolution(uint8_t bits)
246246
{
247+
if (bits > 16)
248+
{
249+
_analogBits = 16; // max out the resolution when this happens
250+
return AP3_ERR;
251+
}
247252
_analogBits = bits;
253+
return AP3_OK;
248254
}
249255

250256
ap3_err_t ap3_adc_setup()
@@ -652,15 +658,28 @@ ap3_err_t servoWriteResolution(uint8_t res)
652658
return AP3_OK;
653659
}
654660

661+
uint8_t getServoResolution()
662+
{
663+
return(_servoWriteBits);
664+
}
665+
655666
ap3_err_t servoWrite(uint8_t pin, uint32_t val)
667+
{
668+
return(servoWrite(pin, val, 544, 2400)); //Call servoWrite with Arduino default min/max microseconds. See: https://www.arduino.cc/en/Reference/ServoAttach
669+
}
670+
671+
ap3_err_t servoWrite(uint8_t pin, uint32_t val, uint16_t minMicros, uint16_t maxMicros)
656672
{
657673
// Determine the high time based on input value and the current resolution setting
658674
uint32_t fsv = (0x01 << _servoWriteBits); // full scale value for the current resolution setting
659675
val = val % fsv; // prevent excess
660676
uint32_t clk = AM_HAL_CTIMER_HFRC_3MHZ; // Using 3 MHz to get fine-grained control up to 20 ms wide
661677
uint32_t fw = 60000; // 20 ms wide frame
662-
uint32_t max = 6000; // max width of RC pwm pulse is 2 ms or 6000 counts
663-
uint32_t min = 3000; // min width of RC pwm pulse is 1 ms or 3000 counts
678+
679+
//Convert microSeconds to PWM counts.
680+
uint32_t min = minMicros * 3;
681+
uint32_t max = maxMicros * 3;
682+
664683
uint32_t th = (uint32_t)(((max - min) * val) / fsv) + min;
665684

666685
return ap3_pwm_output(pin, th, fw, clk);

cores/arduino/ard_sup/ap3_analog.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -43,13 +43,15 @@ ap3_err_t ap3_change_channel(ap3_gpio_pad_t padNumber);
4343

4444
bool power_adc_disable();
4545
uint16_t analogRead(uint8_t pinNumber);
46-
void analogReadResolution(uint8_t bits);
46+
ap3_err_t analogReadResolution(uint8_t bits);
4747

4848
ap3_err_t ap3_pwm_output(uint8_t pin, uint32_t th, uint32_t fw, uint32_t clk);
4949
ap3_err_t analogWriteResolution(uint8_t res);
5050
ap3_err_t analogWrite(uint8_t pin, uint32_t val);
5151
ap3_err_t servoWriteResolution(uint8_t res);
52+
uint8_t getServoResolution();
5253
ap3_err_t servoWrite(uint8_t pin, uint32_t val);
54+
ap3_err_t servoWrite(uint8_t pin, uint32_t val, uint16_t minMicros, uint16_t maxMicros);
5355

5456
ap3_err_t tone(uint8_t pin, uint32_t freq);
5557
ap3_err_t tone(uint8_t pin, uint32_t freq, uint32_t duration);

cores/arduino/ard_sup/ap3_gpio.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ extern const am_hal_gpio_pincfg_t g_AM_HAL_GPIO_INPUT_PULLDOWN;
4545
#define AP3_GPIO_IS_VALID(pad) ((pad >= 0) && (pad < AP3_GPIO_MAX_PADS))
4646

4747
extern ap3_gpio_pad_t ap3_gpio_pin2pad(ap3_gpio_pin_t pin);
48-
#define AP3_GPIO_PAD_UNUSED (-1)
48+
#define AP3_GPIO_PAD_UNUSED (255)
4949

5050
#define AP3_GPIO_DEFAULT_PINCFG AP3_GPIO_PINCFG_NULL
5151

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
/*
2+
Author: Nathan Seidle
3+
SparkFun Electronics
4+
Created: August 18th, 2019
5+
License: MIT. See SparkFun Arduino Apollo3 Project for more information
6+
7+
Purchasing from SparkFun helps write code like this and helps us
8+
release products open source so that we can help each other learn: https://www.sparkfun.com/artemis
9+
10+
This example demonstrates the control of a servo on pin 8 on the RedBoard Artemis. Any PWM
11+
pin can control a servo.
12+
13+
Hardware Connections:
14+
Load this code
15+
Connect a Servo to pin 18:
16+
Red Wire -> 3.3V or 5V
17+
Black Wire -> GND
18+
Signal (Yellow or White) -> 8
19+
20+
The servo will rotate back and forth.
21+
*/
22+
23+
#include <Servo.h>
24+
25+
Servo myServo;
26+
27+
int pos = 0;
28+
29+
void setup()
30+
{
31+
Serial.begin(9600);
32+
Serial.println("SparkFun Servo Example");
33+
34+
myServo.attach(8);
35+
}
36+
37+
void loop()
38+
{
39+
//Sweep
40+
for (pos = 0; pos <= 180; pos++) { // goes from 0 degrees to 180 degrees
41+
myServo.write(pos); // tell servo to go to position in variable 'pos'
42+
delay(5); // waits 15ms for the servo to reach the position
43+
}
44+
for (pos = 180; pos >= 0; pos--) { // goes from 180 degrees to 0 degrees
45+
myServo.write(pos); // tell servo to go to position in variable 'pos'
46+
delay(5); // waits 15ms for the servo to reach the position
47+
}
48+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
/*
2+
Author: Nathan Seidle
3+
SparkFun Electronics
4+
Created: August 18th, 2019
5+
License: MIT. See SparkFun Arduino Apollo3 Project for more information
6+
7+
Purchasing from SparkFun helps write code like this and helps us
8+
release products open source so that we can help each other learn: https://www.sparkfun.com/artemis
9+
10+
This example demonstrates controlling two servos.
11+
12+
Hardware Connections:
13+
Load this code
14+
Connect a Servo to pin 18:
15+
Red Wire -> 3.3V or 5V
16+
Black Wire -> GND
17+
Signal (Yellow or White) -> 8
18+
19+
The servo will rotate back and forth.
20+
*/
21+
22+
#include <Servo.h>
23+
24+
Servo myServoA;
25+
Servo myServoB;
26+
27+
int pos = 0;
28+
29+
void setup()
30+
{
31+
Serial.begin(9600);
32+
Serial.println("SparkFun Servo Example");
33+
34+
myServoA.attach(8);
35+
myServoB.attach(7);
36+
}
37+
38+
void loop()
39+
{
40+
//Sweep
41+
for (pos = 0; pos <= 180; pos++) {
42+
myServoA.write(pos);
43+
myServoB.write(180 - pos);
44+
delay(5);
45+
}
46+
for (pos = 180; pos >= 0; pos--) {
47+
myServoA.write(pos);
48+
myServoB.write(180 - pos);
49+
delay(5);
50+
}
51+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
/*
2+
Author: Nathan Seidle
3+
SparkFun Electronics
4+
Created: August 18th, 2019
5+
License: MIT. See SparkFun Arduino Apollo3 Project for more information
6+
7+
Purchasing from SparkFun helps write code like this and helps us
8+
release products open source so that we can help each other learn: https://www.sparkfun.com/artemis
9+
10+
Different servos have different end points. Arduino defaults to 544us (min) and 2400us (max).
11+
These however can be changed at startup. For more info see: https://www.arduino.cc/en/Reference/ServoAttach
12+
13+
Hardware Connections:
14+
Load this code
15+
Connect a Servo to pin 18:
16+
Red Wire -> 3.3V or 5V
17+
Black Wire -> GND
18+
Signal (Yellow or White) -> 8
19+
20+
The servo will rotate back and forth.
21+
*/
22+
23+
#include <Servo.h>
24+
25+
Servo myServoA;
26+
27+
void setup()
28+
{
29+
Serial.begin(9600);
30+
Serial.println("SparkFun Servo Example");
31+
32+
myServoA.attach(8, 500, 2600); //Increase min/max to drive servo fully
33+
}
34+
35+
void loop()
36+
{
37+
myServoA.write(180); //Go to max position
38+
delay(2000);
39+
myServoA.write(0); //Go to min position
40+
delay(2000);
41+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
/*
2+
Author: Nathan Seidle
3+
SparkFun Electronics
4+
Created: August 18th, 2019
5+
License: MIT. See SparkFun Arduino Apollo3 Project for more information
6+
7+
Purchasing from SparkFun helps write code like this and helps us
8+
release products open source so that we can help each other learn: https://www.sparkfun.com/artemis
9+
10+
Arduino defaults to 8-pin PWM resolution. This works for the majority of servos but can
11+
be increased for projects that need it.
12+
13+
servoWriteResolution()
14+
getServoResolution()
15+
16+
Are provided for changing and reading the resolution setting.
17+
18+
Hardware Connections:
19+
Load this code
20+
Connect a Servo to pin 18:
21+
Red Wire -> 3.3V or 5V
22+
Black Wire -> GND
23+
Signal (Yellow or White) -> 8
24+
25+
The servo will rotate back and forth.
26+
*/
27+
28+
#include <Servo.h>
29+
30+
Servo myServoA;
31+
32+
void setup()
33+
{
34+
Serial.begin(9600);
35+
Serial.println("SparkFun Servo Example");
36+
37+
myServoA.attach(8);
38+
39+
servoWriteResolution(10); //Increase to 10-bit resolution. 16-bit is max.
40+
41+
int currentRes = getServoResolution();
42+
Serial.print("Current resolution: ");
43+
Serial.println(currentRes);
44+
}
45+
46+
void loop()
47+
{
48+
myServoA.write(180); //Go to max position
49+
delay(2000);
50+
myServoA.write(0); //Go to min position
51+
delay(2000);
52+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
/*
2+
Author: Nathan Seidle
3+
SparkFun Electronics
4+
Created: August 18th, 2019
5+
License: MIT. See SparkFun Arduino Apollo3 Project for more information
6+
7+
Purchasing from SparkFun helps write code like this and helps us
8+
release products open source so that we can help each other learn: https://www.sparkfun.com/artemis
9+
10+
This example shows how to write to the servo in microseconds instead of position. This
11+
is helpful for find the min/max us settings for a given servo manufacturer.
12+
13+
Hardware Connections:
14+
Load this code
15+
Connect a Servo to RX1:
16+
Red Wire -> 3.3V or 5V
17+
Black Wire -> GND
18+
Signal (Yellow or White) -> RX1
19+
20+
The servo will rotate back and forth.
21+
*/
22+
23+
#include <Servo.h>
24+
25+
Servo myServo;
26+
27+
void setup()
28+
{
29+
Serial.begin(9600);
30+
Serial.println("SparkFun Servo Example");
31+
32+
myServo.attach(8);
33+
34+
myServo.writeMicroseconds(600); //Servo will go to very near the 0 degree position
35+
}
36+
37+
void loop()
38+
{
39+
}

0 commit comments

Comments
 (0)