Skip to content
Toggle navigation
P
Projects
G
Groups
S
Snippets
Help
dmpada
/
eriala-2024
This project
Loading...
Sign in
Toggle navigation
Go to a project
Project
Repository
Issues
0
Merge Requests
0
Pipelines
Wiki
Snippets
Members
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Commit
61d1d3fb
authored
Sep 30, 2024
by
Risto Heinsar
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
added lab 4 public demo codes
parents
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
274 additions
and
0 deletions
lab4_demo_qti_calibration/lab4_demo_qti_calibration.ino
lab4_demo_servo_calibrate/lab4_demo_servo_calibrate.ino
lab4_demo_servo_move/lab4_demo_servo_move.ino
lab4_demo_ultrasonic/lab4_demo_ultrasonic.ino
lab4_demo_qti_calibration/lab4_demo_qti_calibration.ino
0 → 100644
View file @
61d1d3fb
#define BUTTON_PIN 2
#define LEFT_QTI_PIN A0
#define MIDDLE_QTI_PIN A1
#define RIGHT_QTI_PIN A2
#define NUM_OF_MEASUREMENTS 10
const
uint8_t
debounceDelay
=
50
;
// the debounce time; increase if the output flickers
void
setup
()
{
Serial
.
begin
(
9600
);
pinMode
(
BUTTON_PIN
,
INPUT
);
}
void
loop
()
{
Serial
.
println
(
"Leiame QTI sensorite tumeda ja heleda pinna keskmise väärtuse."
);
Serial
.
println
(
"Pane roboti kõik QTI sensorid tumedale pinnale ja vajuta nuppu."
);
WaitForBtnClick
();
uint16_t
darkSurface
=
MeasureQtiAverage
();
Serial
.
print
(
"Tumeda pinna keskmine väärtus on: "
);
Serial
.
println
(
darkSurface
);
Serial
.
println
(
"Pane roboti kõik QTI sensorid heledale pinnale ja vajuta nuppu."
);
WaitForBtnClick
();
uint16_t
lightSurface
=
MeasureQtiAverage
();
Serial
.
print
(
"Heleda pinna keskmine väärtus on: "
);
Serial
.
println
(
lightSurface
);
Serial
.
print
(
"Soovituslik ""qti_threshold"" väärtus on: "
);
Serial
.
println
((
lightSurface
+
darkSurface
)
/
2
);
Serial
.
println
(
"Uuesti mõõtmiseks vajuta nuppu."
);
WaitForBtnClick
();
Serial
.
println
(
"------------------------------------------------------------------------"
);
}
uint16_t
ReadQti
(
uint8_t
qtiPin
)
{
digitalWrite
(
qtiPin
,
HIGH
);
// Lülitame infrapuna sisse
delayMicroseconds
(
1000
);
// Ootame 1 ms
digitalWrite
(
qtiPin
,
LOW
);
// Lülitame infrapuna välja
return
analogRead
(
qtiPin
);
// Loeme kondensaatorilt tulemuse
}
void
WaitForBtnClick
()
{
while
(
ButtonRead
()
!=
true
);
}
uint16_t
MeasureQtiAverage
(
void
)
{
uint16_t
leftQtiSum
=
0
;
uint16_t
middleQtiSum
=
0
;
uint16_t
rightQtiSum
=
0
;
/* Summeerime üle N mõõtmise */
for
(
uint8_t
i
=
0
;
i
<
NUM_OF_MEASUREMENTS
;
i
++
)
{
leftQtiSum
+=
ReadQti
(
LEFT_QTI_PIN
);
middleQtiSum
+=
ReadQti
(
MIDDLE_QTI_PIN
);
rightQtiSum
+=
ReadQti
(
RIGHT_QTI_PIN
);
delay
(
100
);
}
/* Leiame kõigi sensorite keskmised tulemused*/
uint16_t
leftQtiAverage
=
leftQtiSum
/
NUM_OF_MEASUREMENTS
;
uint16_t
middleQtiAverage
=
middleQtiSum
/
NUM_OF_MEASUREMENTS
;
uint16_t
rightQtiAverage
=
rightQtiSum
/
NUM_OF_MEASUREMENTS
;
Serial
.
println
(
"Sensorite kesmine väärtus:"
);
Serial
.
println
(
"Vasak | Keskmine | Parem"
);
Serial
.
print
(
leftQtiAverage
);
Serial
.
print
(
"
\t
"
);
Serial
.
print
(
middleQtiAverage
);
Serial
.
print
(
"
\t
"
);
Serial
.
println
(
rightQtiAverage
);
/* Leiame pinna üldise keskmise */
uint16_t
surface
=
(
leftQtiSum
+
middleQtiSum
+
rightQtiSum
)
/
(
NUM_OF_MEASUREMENTS
*
3
);
return
surface
;
}
/* Compacted version of https://docs.arduino.cc/built-in-examples/digital/Debounce/ */
bool
ButtonRead
()
{
static
bool
lastButtonState
=
LOW
;
static
uint32_t
lastDebounceTime
=
0
;
static
bool
buttonState
=
LOW
;
bool
btnReadValue
=
digitalRead
(
BUTTON_PIN
);
if
(
btnReadValue
!=
lastButtonState
)
{
lastDebounceTime
=
millis
();
}
if
((
millis
()
-
lastDebounceTime
)
>
debounceDelay
)
{
if
(
btnReadValue
!=
buttonState
)
{
buttonState
=
btnReadValue
;
if
(
buttonState
==
HIGH
)
{
return
true
;
}
}
}
lastButtonState
=
btnReadValue
;
return
false
;
}
lab4_demo_servo_calibrate/lab4_demo_servo_calibrate.ino
0 → 100644
View file @
61d1d3fb
#include <Servo.h>
#define RIGHT_LED_PIN 7
#define LEFT_LED_PIN 8
/* Servomootorite viigud */
#define RIGHT_SERVO_PIN 5
#define LEFT_SERVO_PIN 6
/* Servomootorite impulsside pikkused */
#define SERVO_MIN_PULSE 1300
#define SERVO_MAX_PULSE 1700
#define SERVO_STANDSTILL 1500
Servo
leftWheel
;
Servo
rightWheel
;
const
uint16_t
tickDelay
=
1000
;
void
setup
()
{
/* LEDid väljundiks */
pinMode
(
LEFT_LED_PIN
,
OUTPUT
);
pinMode
(
RIGHT_LED_PIN
,
OUTPUT
);
/* Konfigureerime servomootorid */
leftWheel
.
attach
(
LEFT_SERVO_PIN
,
SERVO_MIN_PULSE
,
SERVO_MAX_PULSE
);
rightWheel
.
attach
(
RIGHT_SERVO_PIN
,
SERVO_MIN_PULSE
,
SERVO_MAX_PULSE
);
/* Anname servodemootorite külge võtmiseks hetke aega */
delay
(
10
);
/* Seadistame servomootorid seisvale asendile */
leftWheel
.
writeMicroseconds
(
SERVO_STANDSTILL
);
rightWheel
.
writeMicroseconds
(
SERVO_STANDSTILL
);
}
void
loop
()
{
static
bool
ledState
=
false
;
digitalWrite
(
RIGHT_LED_PIN
,
ledState
);
digitalWrite
(
LEFT_LED_PIN
,
!
ledState
);
ledState
=
!
ledState
;
delay
(
tickDelay
);
}
lab4_demo_servo_move/lab4_demo_servo_move.ino
0 → 100644
View file @
61d1d3fb
#include <Servo.h>
#define RIGHT_SERVO_PIN 5
#define LEFT_SERVO_PIN 6
#define SERVO_MIN_PULSE 1300
#define SERVO_MAX_PULSE 1700
#define SERVO_STANDSTILL 1500
Servo
leftWheel
;
Servo
rightWheel
;
void
setup
()
{
/* Konfigureerime servomootorid */
leftWheel
.
attach
(
LEFT_SERVO_PIN
,
SERVO_MIN_PULSE
,
SERVO_MAX_PULSE
);
rightWheel
.
attach
(
RIGHT_SERVO_PIN
,
SERVO_MIN_PULSE
,
SERVO_MAX_PULSE
);
/* Anname servodemootorite külge võtmiseks hetke aega */
delay
(
10
);
/* Seadistame servomootorid seisvale asendile */
SetWheels
(
SERVO_STANDSTILL
,
SERVO_STANDSTILL
);
}
void
loop
()
{
/* Liigub edasi aeglaselt */
SetWheels
(
1550
,
1450
);
delay
(
1000
);
/* Seisab pool sekundit */
SetWheels
(
SERVO_STANDSTILL
,
SERVO_STANDSTILL
);
delay
(
500
);
/* Liigub tagasi aeglaselt */
SetWheels
(
1450
,
1550
);
delay
(
1000
);
/* Seisab pool sekundit */
SetWheels
(
SERVO_STANDSTILL
,
SERVO_STANDSTILL
);
delay
(
500
);
}
void
SetWheels
(
int
leftWheelImpulseLength
,
int
rightWheelImpulseLength
)
{
leftWheel
.
writeMicroseconds
(
leftWheelImpulseLength
);
rightWheel
.
writeMicroseconds
(
rightWheelImpulseLength
);
}
lab4_demo_ultrasonic/lab4_demo_ultrasonic.ino
0 → 100644
View file @
61d1d3fb
#define BUTTON_PIN 2
#define SONIC_ECHO_PIN 3
#define SONIC_TRIG_PIN 4
const
uint8_t
debounceDelay
=
50
;
void
setup
()
{
/* Käivitame jadaühenduse */
Serial
.
begin
(
9600
);
/* Seadistame surunupu */
pinMode
(
BUTTON_PIN
,
INPUT
);
/* Seadistame ultraheli sisendi ja väljundi */
pinMode
(
SONIC_TRIG_PIN
,
OUTPUT
);
pinMode
(
SONIC_ECHO_PIN
,
INPUT
);
}
void
loop
()
{
if
(
ButtonRead
())
{
float
distance
=
GetDistInCm
();
Serial
.
print
(
"Roboti kaugus objektist on: "
);
Serial
.
println
(
distance
);
}
}
float
GetDistInCm
()
{
/* Saadame ultrahelilaine välja, kestvus 10 us */
digitalWrite
(
SONIC_TRIG_PIN
,
HIGH
);
delayMicroseconds
(
10
);
digitalWrite
(
SONIC_TRIG_PIN
,
LOW
);
/* Loeme signaali peegeldumise aja */
uint16_t
echoTime
=
pulseIn
(
SONIC_ECHO_PIN
,
HIGH
);
/* Asenda tagastus korrektse valemiga, mille leiad andmelehelt */
return
0.0
f
;
}
bool
ButtonRead
()
{
static
bool
lastButtonState
=
LOW
;
static
uint32_t
lastDebounceTime
=
0
;
static
bool
buttonState
=
LOW
;
bool
btnReadValue
=
digitalRead
(
BUTTON_PIN
);
if
(
btnReadValue
!=
lastButtonState
)
{
lastDebounceTime
=
millis
();
}
if
((
millis
()
-
lastDebounceTime
)
>
debounceDelay
)
{
if
(
btnReadValue
!=
buttonState
)
{
buttonState
=
btnReadValue
;
if
(
buttonState
==
HIGH
)
{
return
true
;
}
}
}
lastButtonState
=
btnReadValue
;
return
false
;
}
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment