Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
MechaRaptor - Arduino Controller
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Iterations
Wiki
Requirements
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Locked files
Build
Pipelines
Jobs
Pipeline schedules
Test cases
Artifacts
Deploy
Releases
Package Registry
Container Registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Code review analytics
Issue analytics
Insights
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Aerospace and Mechanical Engineering
tlambert
MechaRaptor - Arduino Controller
Commits
bf353938
Verified
Commit
bf353938
authored
2 years ago
by
Thomas Lambert
Browse files
Options
Downloads
Patches
Plain Diff
refact: use define instead of const
Signed-off-by:
Thomas Lambert
<
t.lambert@uliege.be
>
parent
5552ece4
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
controller/controller.ino
+23
-25
23 additions, 25 deletions
controller/controller.ino
with
23 additions
and
25 deletions
controller/controller.ino
+
23
−
25
View file @
bf353938
...
...
@@ -21,37 +21,36 @@
// Include Servo library to generate the PWM signal to control the motors
#include
<Servo.h>
// Declare pins
byte
servoPin1
=
10
;
// ESC 1
byte
servoPin2
=
9
;
// ESC 2
byte
switchPin
=
7
;
// ON/OFF switch (safety feature)
// Constants
#define SERVO_PIN_1 10 // ESC 1
#define SERVO_PIN_2 9 // ESC 2
#define SWITCH_PIN 7 // ON/OFF switch (mode control)
#define MAX_SIG 2000 // Max signal to the ESC [ms]
#define MIN_SIG 1000 // Min signal to the ESC [ms]
#define MAX_FREQ 10.0 // Maximum frequency
#define MIN_FREQ 1.0 // Minimum frequency
#define MAX_RPM 6000 // Motor maximum RPM (set in ESC)
#define MIN_RPM 1000 // Motor minimum RPM (set in ESC)
// Create servo objects to control the ESC
Servo
ESC1
;
Servo
ESC2
;
// Declare constants
const
float
maxFreq
=
10.0
;
// Maximum frequency
const
float
minFreq
=
1.0
;
// Minimum frequency
const
int
maxRPM
=
6000
;
// Motor maximum RPM (set in ESC)
const
int
minRPM
=
1000
;
// Motor minimum RPM (set in ESC)
// Declare global variables
float
freq
=
0
;
String
mode
;
void
setup
()
{
// Initialize components
Serial
.
begin
(
9600
);
Serial
.
begin
(
9600
);
//115200 when we will use angle sensors
ESC1
.
attach
(
servoPin
1
,
1000
,
2000
);
// (pin, min pulse width, max pulse width)
ESC2
.
attach
(
servoPin
2
,
1000
,
2000
);
// (pin, min pulse width, max pulse width)
pinMode
(
switchPin
,
INPUT
);
ESC1
.
attach
(
SERVO_PIN_
1
,
1000
,
2000
);
// (pin, min pulse width, max pulse width)
ESC2
.
attach
(
SERVO_PIN_
2
,
1000
,
2000
);
// (pin, min pulse width, max pulse width)
pinMode
(
SWITCH_PIN
,
INPUT
);
delay
(
1000
);
// Ensure proper initialization
// Set type of operation and related parameters if applicable
int
switchState
=
digitalRead
(
switchPin
);
int
switchState
=
digitalRead
(
SWITCH_PIN
);
if
(
switchState
==
LOW
){
mode
=
"MANUAL"
;
Serial
.
println
(
"<MANUAL MODE>: Control motors using potentiometer"
);
...
...
@@ -102,8 +101,7 @@ void loop() {
Serial
.
print
(
","
);
Serial
.
print
(
angleR
);
// %6, Right wing angle [deg]
Serial
.
println
(
"*/"
);
// Frame finish sequence [*/]
//delay(1); // Reduce number of data to output
//delay(5); // Reduce number of data to output
}
...
...
@@ -112,23 +110,23 @@ float promptfreq() {
float
input
;
Serial
.
print
(
"Input a flapping frequency between "
);
Serial
.
print
(
minFreq
);
Serial
.
print
(
MIN_FREQ
);
Serial
.
print
(
" and "
);
Serial
.
print
(
maxFreq
);
Serial
.
print
(
MAX_FREQ
);
Serial
.
println
(
" [Hz]"
);
while
(
input
>
maxFreq
or
input
<
minFreq
){
while
(
input
>
MAX_FREQ
or
input
<
MIN_FREQ
){
while
(
Serial
.
available
()
==
0
)
{
// Loop indefinitely while waiting for serial input
}
input
=
Serial
.
parseFloat
();
if
(
input
>
maxFreq
or
input
<
minFreq
)
{
if
(
input
>
MAX_FREQ
or
input
<
MIN_FREQ
)
{
Serial
.
print
(
"Frequency must be between "
);
Serial
.
print
(
minFreq
);
Serial
.
print
(
MIN_FREQ
);
Serial
.
print
(
" and "
);
Serial
.
print
(
maxFreq
);
Serial
.
print
(
MAX_FREQ
);
Serial
.
print
(
" [Hz]. You entered: "
);
Serial
.
println
(
input
);
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment