Do RFID scans only at specified intervals. System sounds are now supported, as well as more sound formats (.ogg, .mp4...).

This commit is contained in:
Fabian Schlenz 2019-08-08 05:31:27 +02:00
parent 815f11591c
commit 393db24175
5 changed files with 95 additions and 54 deletions

View File

@ -1,39 +0,0 @@
This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.
```src/main.c
#include "header.h"
int main (void)
{
...
}
```
Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.
In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot.
Read more about using header files in official GCC documentation:
* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

View File

@ -12,6 +12,7 @@ private:
void _check_rfid();
void _check_serial();
Player* _player;
unsigned long _last_rfid_scan_at = 0;
public:
Controller(Player* p);
void loop();

View File

@ -28,7 +28,8 @@
class Player {
private:
enum state { uninitialized, idle, playing, stopping };
enum state { uninitialized, idle, playing, stopping,
system_sound_while_playing, system_sound_while_stopped };
struct album_state {
uint8_t index;
uint32_t position;
@ -42,10 +43,12 @@ private:
uint16_t _read_wram(uint16_t address);
state _state = state::uninitialized;
void _refill();
bool _refill_needed();
void _flush_and_cancel();
void _flush(uint bytes);
void _set_last_track(const char* album, uint8_t track, uint32_t position);
std::map<String, album_state> _last_tracks;
void _play_file(String filename, uint32_t offset);
void _finish_playing();
void _finish_stopping();
void _mute();
@ -56,6 +59,7 @@ private:
SPISettings* _spi_settings = &_spi_settings_slow;
std::list<String> _files_in_dir(String dir);
String _find_album_dir(String album);
File _file;
uint8_t _buffer[32];
String _playing_album;
@ -74,6 +78,7 @@ public:
bool play_album(String album);
bool play_song(String album, uint8_t song_index, uint32_t offset=0);
void play_system_sound(String filename);
void stop();
bool loop();
void set_volume(uint8_t vol, bool save = true);

View File

@ -13,7 +13,11 @@ Controller::Controller(Player* p) {
}
void Controller::loop() {
_check_rfid();
unsigned long now = millis();
if ((_last_rfid_scan_at < now - RFID_SCAN_INTERVAL) || (now < _last_rfid_scan_at)) {
_check_rfid();
_last_rfid_scan_at = now;
}
_check_serial();
}
@ -44,6 +48,8 @@ void Controller::_check_serial() {
_player->vol_down();
} else if (c==' ') {
_player->play_album("12345678");
} else if (c=='q') {
_player->play_system_sound("12345678/Biene Maja.mp3");
}
}
}

View File

@ -164,6 +164,22 @@ void Player::track_prev() {
play_song(_playing_album, _playing_index - 1);
}
String Player::_find_album_dir(String id) {
String id_with_divider = id + " - ";
File root = SD.open("/");
File entry;
String result = String("");
while ((result.length()==0) && (entry = root.openNextFile())) {
String name = entry.name();
if (entry.isDirectory() && (name.startsWith(id_with_divider) || name.equals(id))) {
result = name;
}
entry.close();
}
root.close();
return result;
}
std::list<String> Player::_files_in_dir(String path) {
Serial.printf("Examining folder %s...\n", path.c_str());
if (!path.startsWith("/")) path = String("/") + path;
@ -174,7 +190,13 @@ std::list<String> Player::_files_in_dir(String path) {
File entry;
while (entry = dir.openNextFile()) {
String filename = entry.name();
if (!entry.isDirectory() && !filename.startsWith(".") && filename.endsWith(".mp3")) {
if (!entry.isDirectory() &&
!filename.startsWith(".") &&
( filename.endsWith(".mp3") ||
filename.endsWith(".ogg") ||
filename.endsWith(".wma") ||
filename.endsWith(".mp4") ||
filename.endsWith(".mpa")) {
//Serial.printf("Adding file %s\n", filename.c_str());
result.push_back(path + filename);
} else {
@ -196,8 +218,15 @@ bool Player::play_album(String album) {
bool Player::play_song(String album, uint8_t index, uint32_t skip_to) {
if (_state != idle) return false;
Serial.printf("Playing song at index %d, offset %d of album %s\n", index, skip_to, album.c_str());
std::list<String> files = _files_in_dir(album);
Serial.printf("Trying to play song at index %d, offset %d of album %s\n", index, skip_to, album.c_str());
String path = _find_album_dir(album);
if (path.length()==0) {
Serial.println("Could not find album.");
return false;
} else {
Serial.printf("Found album in dir '%s'.\n", path.c_str());
}
std::list<String> files = _files_in_dir(path);
Serial.printf("Found %d songs in album\n", files.size());
if (index >= files.size()) {
Serial.println("No matching file found - not playing.");
@ -206,24 +235,45 @@ bool Player::play_song(String album, uint8_t index, uint32_t skip_to) {
//std::list<String>::iterator it = files.begin();
//std::advance(it, index);
String file = *(std::next(files.begin(), index));
Serial.printf("Opening file %s for playback...\n", file.c_str());
_state = playing;
_playing_album = album;
_playing_index = index;
_set_last_track(album.c_str(), index, skip_to);
_play_file(file, skip_to);
return true;
}
void Player::play_system_sound(String filename) {
//String file = String("/system/") + filename;
String file = filename;
if (!SD.exists(file)) {
Serial.printf("File %s does not exist!\n", file.c_str());
return;
}
if (_state == playing) {
stop();
_state = system_sound_while_playing;
} else {
_state = system_sound_while_stopped;
}
_play_file(file, 0);
}
void Player::_play_file(String file, uint32_t file_offset) {
Serial.printf("play_file('%s', %d)\n", file.c_str(), file_offset);
_file = SD.open(file);
if (!_file) return;
Serial.println("Resetting SCI_DECODE_TIME...");
_write_control_register(SCI_DECODE_TIME, 0);
Serial.println("Resetting SS_DO_NOT_JUMP...");
_write_control_register(SCI_STATUS, _read_control_register(SCI_STATUS) & ~SS_DO_NOT_JUMP);
delay(100);
_state = playing;
_playing_album = album;
_playing_index = index;
_refills = 0;
_skip_to = skip_to;
_skip_to = file_offset;
if (_skip_to>0) _mute();
Serial.println("Now playing.");
_set_last_track(album.c_str(), index, 0);
return true;
}
void Player::_flush(uint bytes) {
@ -260,9 +310,11 @@ void Player::_flush_and_cancel() {
}
void Player::stop() {
if (_state != playing) return;
if (_state != playing /* && _state != system_sound_while_playing && _state != system_sound_while_stopped*/) return;
Serial.println("Stopping.");
_set_last_track(_playing_album.c_str(), _playing_index, (uint32_t)_file.position());
if (_state == playing) {
_set_last_track(_playing_album.c_str(), _playing_index, (uint32_t)_file.position());
}
_state = stopping;
_stop_delay = 0;
_write_control_register(SCI_MODE, _read_control_register(SCI_MODE) | SM_CANCEL);
@ -298,6 +350,15 @@ void Player::_refill() {
// File is over.
Serial.println("EOF reached.");
_finish_playing();
if (_state == system_sound_while_playing) {
_finish_stopping();
play_album(_playing_album);
return;
} else if (_state == system_sound_while_stopped) {
_finish_stopping();
return;
}
_finish_stopping();
bool result = play_song(_playing_album, _playing_index + 1);
if (!result) {
@ -324,8 +385,15 @@ void Player::_refill() {
}
}
bool Player::_refill_needed() {
return _state==playing ||
_state==stopping ||
_state==system_sound_while_playing ||
_state==system_sound_while_stopped;
}
bool Player::loop() {
if (digitalRead(DREQ) && (_state==playing || _state==stopping)) {
if (digitalRead(DREQ) && _refill_needed()) {
_refill();
return true;
}