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
d643cd9d
Verified
Commit
d643cd9d
authored
2 years ago
by
Thomas Lambert
Browse files
Options
Downloads
Patches
Plain Diff
feat: add psu monitoring
parent
e6ac1279
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
CHANGELOG.md
+1
-0
1 addition, 0 deletions
CHANGELOG.md
README.md
+13
-2
13 additions, 2 deletions
README.md
controller/controller.ino
+83
-25
83 additions, 25 deletions
controller/controller.ino
controller/mechaRaptor.json
+67
-5
67 additions, 5 deletions
controller/mechaRaptor.json
with
164 additions
and
32 deletions
CHANGELOG.md
+
1
−
0
View file @
d643cd9d
...
...
@@ -12,6 +12,7 @@ to [Semantic Versioning][sem_ver].
-
**Doc**
: Changelog
-
**Controller**
: Complete control over Serial
-
**Acquisition**
: Angle sensor acquisition
-
**Acquisition**
: PSU current and tension monitoring
### Changed
...
...
This diff is collapsed.
Click to expand it.
README.md
+
13
−
2
View file @
d643cd9d
...
...
@@ -51,14 +51,22 @@ the motor.
## Data logging and visualization
The controller returns the important data through the serial connection.
Besides controlling the system, the Arduino also logs the input data and some
measurements. The most important data are:
-
ESC input setting
-
Wing angles (for each wing)
-
PSU current and tension
These logged data are transmitted through the serial connection in order to be
saved on a separate laptop and analyzed later.
A
[
_json_ configuration file
](
controller/mechaRaptor.json
)
is provided in order
to visualize the output stream in real time with [serial-studio]. This also
allows the logging and retention of all data in _csv_ spreadsheets for future
analysis.
## Material
##
Bill of
Material
s
The system consists in two completely independent sets of wings, powered
separately.
...
...
@@ -79,6 +87,8 @@ wing, which is measured using absolute magnetic rotary encoders.
|
**Encoders**
|
[
Broadcom AEAT 6012
][
AEAT612
]
| Flapping angle measurement |
|
**Potentiometer**
| N/A | Manual control of RPM|
|
**ON/OFF switch**
| N/A | Switch between
`Serial`
and
`Manual`
control |
|
**Resistors**
| N/A | Voltage divider, noise reduction |
|
**Current sensor**
|
[
Allegro SEN0098
][
SEN0098
]
| PSU current logging |
## Schematics
...
...
@@ -91,3 +101,4 @@ To Do (January 2023)
[
arduino
]:
<
https://store.arduino.cc/products/arduino-uno-rev3
>
[
elektro
]:
<
https://elektroautomatik.de
>
[
AEAT612
]:
<
https://docs.broadcom.com/doc/AV02-0188EN
>
[
SEN0098
]:
https://www.allegromicro.com/~/media/Files/Datasheets/ACS758-Datasheet.ashx
This diff is collapsed.
Click to expand it.
controller/controller.ino
+
83
−
25
View file @
d643cd9d
...
...
@@ -21,30 +21,54 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
#include
<Servo.h>
// Control ESC by sending appropriate PWM signal
/*******************************************************************************
Macros (
use
for pins only)
Macros (for pins
and fixed components
only
!
)
*******************************************************************************/
// Pins
#define ESC1_PIN 10 // ESC Front motor
#define ESC2_PIN 9 // ESC Aft motor
#define SWITCH_PIN 7 // ON/OFF switch (mode control)
#define CLK_PIN 2 // Encoder CLK
#define DO_PIN 8 // Encoder Digital Output
#define POT_PIN A0 // Potentiometer
#define CLK_PIN 2 // Encoder CLK
#define DO_PIN 8 // Encoder Digital Output
#define CSN_PINS { 3, 4, 5, 6 } // Encoder Chip Select pins
#define CUR1_PIN A1 // Current measurement for Front motor
#define CUR2_PIN A2 // Current measurement for Aft motor
#define TENS1_PIN A3 // Tension measurement for Front motor
#define TENS2_PIN A4 // Tension measurement for Aft motor
// Values
#define DIV_RES1 9000.0 // Resistance of R1 in the voltage dividers
#define DIV_RES2 1000.0 // Resistance of R2 in the voltage dividers
#define SEN0098_VCC 5 // Supply voltage of the current sensors
#define SEN0098_SENSI 20.0 // [FIXME] VERIFY!
#define SEN0098_VIOUT 0.12 // [FIXME] VERIFY!
#define SEN0098_OFFSET 0.12 // [FIXME] VERIFY!
#define GEAR_RATIO 0.1 // Gear ratio between motor and wings
/*******************************************************************************
Globals
Globals
(for things that I can change manually)
*******************************************************************************/
const
uint8_t
gCSN_PINS
[]
=
{
3
,
4
,
5
,
6
};
// Encoder Chip Select pins
// Constant values that can be tweaked here or in the ESC before run
const
int
gMAX_SIG
=
2000
;
// Max signal to the ESC [ms]
const
int
gMIN_SIG
=
1000
;
// Min signal to the ESC [ms]
const
int
gMAX_RPM
=
3000
;
// Motor maximum RPM (set in ESC)
const
int
gMIN_RPM
=
750
;
// Motor minimum RPM (set in ESC)
const
float
gGEAR_RATIO
=
0.1
;
// Gear ratio between motor and wings
const
int
gMAX_ESC_VAL
=
160
;
// Value at which motor is at max RPM
const
int
gMIN_ESC_VAL
=
40
;
// Min value for ESC to start motor (trial-error)
const
int
gMAX_RPM
=
3000
;
// Motor maximum RPM (set in ESC)
const
int
gMIN_RPM
=
750
;
// Motor minimum RPM (set in ESC)
const
int
gMAX_ESC_VAL
=
160
;
// Value at which motor is at max RPM
const
int
gMIN_ESC_VAL
=
40
;
// Min value for ESC to start motor (trial-error)
const
uint8_t
gCSN_PINS
[]
=
CSN_PINS
;
// Encoder Chip Select pins
const
float
gCUR_FACT
=
SEN0098_SENSI
/
1000.0
;
// Factor for current measurement
const
float
gCUR_QOV
=
SEN0098_VIOUT
*
SEN0098_VCC
;
// Other
Servo
gEsc1
;
// ESC for front motor
Servo
gEsc2
;
// ESC for aft motor
...
...
@@ -59,23 +83,24 @@ void setup() {
//Serial.begin(9600); //[DEBUG]: For debugging only
Serial
.
begin
(
115200
);
// Need for good precision
// Init ESCs
Serial
.
print
(
"[INFO]: Attaching ESCs ... "
);
delay
(
5000
);
// Prevents motor from starting automatically with serial
gEsc1
.
attach
(
ESC1_PIN
,
gMIN_SIG
,
gMAX_SIG
);
gEsc2
.
attach
(
ESC2_PIN
,
gMIN_SIG
,
gMAX_SIG
);
Serial
.
println
(
"done!"
);
// Init switch
pinMode
(
SWITCH_PIN
,
INPUT
);
// [DEBUG] Comment all that as long as PCB not properly soldered
//for (int i = 0; i < sizeof(gCSN_PINS); i++) {
// pinMode(gCSN_PINS[i], OUTPUT);
// digitalWrite(gCSN_PINS[i], HIGH);
//}
//pinMode(CLK_PIN, OUTPUT);
//pinMode(DO_PIN, INPUT);
//digitalWrite(CLK_PIN, HIGH);
// Init angle sensors
for
(
int
i
=
0
;
i
<
sizeof
(
gCSN_PINS
);
i
++
)
{
pinMode
(
gCSN_PINS
[
i
],
OUTPUT
);
digitalWrite
(
gCSN_PINS
[
i
],
HIGH
);
}
pinMode
(
CLK_PIN
,
OUTPUT
);
pinMode
(
DO_PIN
,
INPUT
);
digitalWrite
(
CLK_PIN
,
HIGH
);
// Initialize modes
int
switch_state
=
digitalRead
(
SWITCH_PIN
);
...
...
@@ -107,8 +132,8 @@ void setup() {
*******************************************************************************/
void
loop
()
{
int
potent
=
analogRead
(
A0
);
// Potentiometer value
unsigned
int
wing_angles
[
4
];
// Wing angles (1L, 1R, 2L, 2R)
int
potent
=
analogRead
(
POT_PIN
);
// Potentiometer value
unsigned
int
wing_angles
[
sizeof
(
gCSN_PINS
)
];
// Wing angles (1L, 1R, 2L, 2R)
if
(
gMode
==
"SERIAL"
and
Serial
.
available
())
{
...
...
@@ -132,7 +157,12 @@ void loop() {
wing_angles
[
i
]
=
ReadSensor
(
gCSN_PINS
[
i
]);
}
SerialPrint
(
gMode
,
potent
,
gEsc_val
,
wing_angles
);
// Read current and power
float
psu_cur
[
2
],
psu_vol
[
2
];
GetPsu
(
TENS1_PIN
,
CUR1_PIN
,
psu_vol
[
0
],
psu_cur
[
0
]);
GetPsu
(
TENS2_PIN
,
CUR2_PIN
,
psu_vol
[
1
],
psu_cur
[
1
]);
SerialPrint
(
gMode
,
potent
,
gEsc_val
,
wing_angles
,
psu_vol
,
psu_cur
);
}
...
...
@@ -193,7 +223,7 @@ int FreqToEsc(float freq) {
// Converts RPM to Flapping frequency
float
RpmToFreq
(
int
rpm
)
{
return
rpm
*
g
GEAR_RATIO
/
60.0
;
return
rpm
*
GEAR_RATIO
/
60.0
;
}
...
...
@@ -241,7 +271,7 @@ unsigned int ReadSensor(uint8_t csn) {
// Output data to use with serial-studio
void
SerialPrint
(
String
mode
,
int
potent
,
int
esc_val
,
unsigned
int
wing_angles
[])
{
void
SerialPrint
(
String
mode
,
int
potent
,
int
esc_val
,
unsigned
int
wing_angles
[]
,
float
psu_vol
[],
float
psu_cur
[]
)
{
float
freq
=
map
(
esc_val
,
0
,
180
,
0
,
RpmToFreq
(
gMAX_RPM
)
*
100.0
)
/
100.0
;
Serial
.
print
(
"/*"
);
...
...
@@ -258,5 +288,33 @@ void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[
Serial
.
print
(
","
);
Serial
.
print
(
wing_angles
[
i
]);
}
for
(
int
i
=
0
;
i
<
sizeof
(
psu_vol
);
i
++
)
{
Serial
.
print
(
","
);
Serial
.
print
(
psu_vol
[
i
]);
Serial
.
print
(
","
);
Serial
.
print
(
psu_cur
[
i
]);
}
Serial
.
println
(
"*/"
);
}
// Measure current consumed by module
float
GetCurrent
(
byte
cur_pin
)
{
float
cur_raw
=
(
5.0
/
1023.0
)
*
analogRead
(
cur_pin
);
float
cur
=
cur_raw
*
-
gCUR_QOV
+
0.007
;
//Trimming vale to make current equal to 0 when no current
return
cur
/
gCUR_FACT
;
// get actual current
}
// Measure the tension provided by the PSU
float
GetTension
(
byte
vol_pin
)
{
int
vol_raw
=
analogRead
(
vol_pin
)
*
(
5.0
/
1023.0
);
return
vol_raw
*
(
DIV_RES1
+
DIV_RES2
)
/
(
DIV_RES2
);
}
// Get the tension and current of a PSU
void
GetPsu
(
byte
vol_pin
,
byte
cur_pin
,
float
&
vol
,
float
&
cur
)
{
vol
=
GetTension
(
vol_pin
);
cur
=
GetCurrent
(
cur_pin
);
}
This diff is collapsed.
Click to expand it.
controller/mechaRaptor.json
+
67
−
5
View file @
d643cd9d
...
...
@@ -62,7 +62,7 @@
"max"
:
180
,
"min"
:
0
,
"title"
:
"ESC val"
,
"units"
:
""
,
"units"
:
"
°
"
,
"value"
:
"%4"
,
"widget"
:
"gauge"
},
...
...
@@ -84,6 +84,68 @@
"title"
:
"Inputs"
,
"widget"
:
""
},
{
"datasets"
:
[
{
"alarm"
:
0
,
"fft"
:
false
,
"fftSamples"
:
1024
,
"graph"
:
false
,
"led"
:
false
,
"log"
:
false
,
"max"
:
0
,
"min"
:
0
,
"title"
:
"1 - Tension"
,
"units"
:
"V"
,
"value"
:
"%10"
,
"widget"
:
""
},
{
"alarm"
:
0
,
"fft"
:
false
,
"fftSamples"
:
1024
,
"graph"
:
false
,
"led"
:
false
,
"log"
:
false
,
"max"
:
0
,
"min"
:
0
,
"title"
:
"1 - Current"
,
"units"
:
"A"
,
"value"
:
"%11"
,
"widget"
:
""
},
{
"alarm"
:
0
,
"fft"
:
false
,
"fftSamples"
:
1024
,
"graph"
:
false
,
"led"
:
false
,
"log"
:
false
,
"max"
:
0
,
"min"
:
0
,
"title"
:
"2 - Tension"
,
"units"
:
"V"
,
"value"
:
"%12"
,
"widget"
:
""
},
{
"alarm"
:
40
,
"fft"
:
false
,
"fftSamples"
:
1024
,
"graph"
:
false
,
"led"
:
false
,
"log"
:
false
,
"max"
:
360
,
"min"
:
0
,
"title"
:
"2 - Current"
,
"units"
:
"A"
,
"value"
:
"%13"
,
"widget"
:
""
}
],
"title"
:
"Power Supplies"
,
"widget"
:
""
},
{
"datasets"
:
[
{
...
...
@@ -96,7 +158,7 @@
"max"
:
0
,
"min"
:
0
,
"title"
:
"Left"
,
"units"
:
"
deg
"
,
"units"
:
"
°
"
,
"value"
:
"%6"
,
"widget"
:
""
},
...
...
@@ -110,7 +172,7 @@
"max"
:
0
,
"min"
:
0
,
"title"
:
"Right"
,
"units"
:
"
deg
"
,
"units"
:
"
°
"
,
"value"
:
"%7"
,
"widget"
:
""
}
...
...
@@ -130,7 +192,7 @@
"max"
:
0
,
"min"
:
0
,
"title"
:
"Left"
,
"units"
:
"
deg
"
,
"units"
:
"
°
"
,
"value"
:
"%8"
,
"widget"
:
""
},
...
...
@@ -144,7 +206,7 @@
"max"
:
0
,
"min"
:
0
,
"title"
:
"Right"
,
"units"
:
"
deg
"
,
"units"
:
"
°
"
,
"value"
:
"%9"
,
"widget"
:
""
}
...
...
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