Work in progress

This commit is contained in:
Rene Zeldenthuis
2024-11-02 21:45:07 +01:00
parent 4b50b52ae0
commit 4dc36fb1e8
12 changed files with 202 additions and 198 deletions

View File

@@ -97,7 +97,7 @@ There are a lot of boards available that are all called ESP32-CAM.
However, there are differences in CPU (type/speed/cores), how the camera is connected, presence of PSRAM or not... However, there are differences in CPU (type/speed/cores), how the camera is connected, presence of PSRAM or not...
To select the right board use the table below and use the configuration that is listed below for your board: To select the right board use the table below and use the configuration that is listed below for your board:
| Board | Image | CPU | SRAM | Flash | PSRAM | Camera | | Site | | Board | Image | CPU | SRAM | Flash | PSRAM | Camera | Extras | Manufacturer site |
|--- |--- |--- |--- |--- | --- |--- |--- |--- | |--- |--- |--- |--- |--- | --- |--- |--- |--- |
| Espressif ESP32-Wrover CAM | ![img](assets/boards/esp32-wrover-cam.jpg) | ESP32 | 520KB | 4Mb | 4MB | OV2640 | | | | Espressif ESP32-Wrover CAM | ![img](assets/boards/esp32-wrover-cam.jpg) | ESP32 | 520KB | 4Mb | 4MB | OV2640 | | |
| AI-Thinker ESP32-CAM | ![img](assets/boards/ai-thinker-esp32-cam-ipex.jpg) ![img](assets/boards/ai-thinker-esp32-cam.jpg) | ESP32-S | 520KB | 4Mb | 4MB | OV2640 | | [https://docs.ai-thinker.com/esp32-cam](https://docs.ai-thinker.com/esp32-cam) | | AI-Thinker ESP32-CAM | ![img](assets/boards/ai-thinker-esp32-cam-ipex.jpg) ![img](assets/boards/ai-thinker-esp32-cam.jpg) | ESP32-S | 520KB | 4Mb | 4MB | OV2640 | | [https://docs.ai-thinker.com/esp32-cam](https://docs.ai-thinker.com/esp32-cam) |

1
dotnet_riscv Submodule

Submodule dotnet_riscv added at 70e3cb657b

View File

@@ -1,8 +1,9 @@
#pragma once #pragma once
#include <micro_rtsp_source.h>
#include <esp_camera.h> #include <esp_camera.h>
class micro_rtsp_camera class micro_rtsp_camera : public micro_rtsp_source
{ {
public: public:
micro_rtsp_camera(); micro_rtsp_camera();
@@ -11,12 +12,12 @@ public:
esp_err_t initialize(camera_config_t *camera_config); esp_err_t initialize(camera_config_t *camera_config);
esp_err_t deinitialize(); esp_err_t deinitialize();
void update_frame(); virtual void update_frame();
uint8_t *data() const { return fb_->buf; } virtual uint8_t *data() const { return fb_->buf; }
size_t width() const { return fb_->width; } virtual size_t width() const { return fb_->width; }
size_t height() const { return fb_->height; } virtual size_t height() const { return fb_->height; }
size_t size() const { return fb_->len; } virtual size_t size() const { return fb_->len; }
private: private:
esp_err_t init_result_; esp_err_t init_result_;

View File

@@ -1,5 +1,6 @@
#pragma once #pragma once
#include <map>
#include <string> #include <string>
class micro_rtsp_requests class micro_rtsp_requests
@@ -8,40 +9,41 @@ public:
std::string process_request(const std::string& request); std::string process_request(const std::string& request);
private: private:
enum rtsp_command // enum rtsp_command
{ // {
rtsp_command_unknown, // rtsp_command_unknown,
rtsp_command_option, // OPTIONS // rtsp_command_options, // OPTIONS
rtsp_command_describe, // DESCRIBE // rtsp_command_describe, // DESCRIBE
rtsp_command_setup, // SETUP // rtsp_command_setup, // SETUP
rtsp_command_play, // PLAY // rtsp_command_play, // PLAY
rtsp_command_teardown // TEARDOWN // rtsp_command_teardown // TEARDOWN
}; // };
const char* available_stream_name_ = "mjpeg/1"; static const std::string available_stream_name_;
rtsp_command parse_command(const std::string &request); //rtsp_command parse_command(const std::string &request);
//static bool parse_cseq(const std::string &line, unsigned long &cseq);
bool parse_client_port(const std::string &request); bool parse_client_port(const std::string &request);
bool parse_cseq(const std::string &request); //bool parse_stream_url(const std::string &request);
bool parse_stream_url(const std::string &request);
std::string date_header(); //static std::string date_header();
std::string rtsp_error(unsigned short code, const std::string& message); static std::string handle_rtsp_error(unsigned long cseq, unsigned short code, const std::string &message);
std::string handle_option(const std::string &request); static std::string handle_options(unsigned long cseq);
std::string handle_describe(const std::string &request); static std::string handle_describe(unsigned long cseq, const std::string &request);
std::string handle_setup(const std::string &request); std::string handle_setup(unsigned long cseq, const std::map<std::string, std::string> &request);
std::string handle_play(const std::string &request); std::string handle_play(unsigned long cseq);
std::string handle_teardown(const std::string &request); std::string handle_teardown(unsigned long cseq);
unsigned long cseq_; //unsigned long cseq_;
std::string host_url_; // std::string host_url_;
unsigned short host_port_; // unsigned short host_port_;
std::string stream_name_; // std::string stream_name_;
bool tcp_transport_; bool tcp_transport_;
unsigned short client_port_; unsigned short start_client_port_;
unsigned short end_client_port_;
unsigned short rtp_streamer_port_; unsigned short rtp_streamer_port_;
unsigned short rtcp_streamer_port_; unsigned short rtcp_streamer_port_;

View File

@@ -13,18 +13,18 @@
class micro_rtsp_server : WiFiServer class micro_rtsp_server : WiFiServer
{ {
public: public:
micro_rtsp_server(micro_rtsp_camera &source, unsigned frame_interval = 100); micro_rtsp_server(micro_rtsp_source &source);
~micro_rtsp_server(); ~micro_rtsp_server();
void begin(unsigned short port = 554); void begin(unsigned short port = 554);
void end(); void end();
unsigned get_frame_interval() { return frame_interval_; } unsigned get_frame_interval() const { return frame_interval_; }
unsigned set_frame_interval(unsigned value) { return frame_interval_ = value; } unsigned set_frame_interval(unsigned value) { return frame_interval_ = value; }
void loop(); void loop();
size_t clients() { return clients_.size(); } size_t clients() const { return clients_.size(); }
class rtsp_client : public WiFiClient, public micro_rtsp_requests class rtsp_client : public WiFiClient, public micro_rtsp_requests
{ {
@@ -36,7 +36,7 @@ public:
}; };
private: private:
micro_rtsp_camera &source_; micro_rtsp_source &source_;
unsigned frame_interval_; unsigned frame_interval_;
unsigned long next_frame_update_; unsigned long next_frame_update_;
unsigned long next_check_client_; unsigned long next_check_client_;

View File

@@ -0,0 +1,16 @@
#pragma once
#include <stddef.h>
#include <stdint.h>
// Interface for a video source
class micro_rtsp_source
{
public:
virtual void update_frame() = 0;
virtual uint8_t *data() const = 0;
virtual size_t width() const = 0;
virtual size_t height() const = 0;
virtual size_t size() const = 0;
};

View File

@@ -1,7 +1,8 @@
#pragma once #pragma once
#include <jpg_section.h> #include <jpg_section.h>
#include <micro_rtp_structs.h> #include <micro_rtsp_camera.h> // Add this line to include the definition of micro_rtsp_camera
#include <micro_rtsp_structs.h>
// https://en.wikipedia.org/wiki/Maximum_transmission_unit // https://en.wikipedia.org/wiki/Maximum_transmission_unit
constexpr size_t max_wifi_mtu = 2304; constexpr size_t max_wifi_mtu = 2304;
@@ -32,11 +33,11 @@ typedef struct __attribute__((packed))
class micro_rtsp_streamer class micro_rtsp_streamer
{ {
public: public:
micro_rtsp_streamer(const uint16_t width, const uint16_t height); micro_rtsp_streamer(const micro_rtsp_source& source);
rtp_over_tcp_hdr_t *create_jpg_packet(const uint8_t *jpg_scan, const uint8_t *jpg_scan_end, uint8_t **jpg_offset, const uint32_t timestamp, const uint8_t *quantization_table_luminance, const uint8_t *quantization_table_chrominance); rtp_over_tcp_hdr_t *create_jpg_packet(const uint8_t *jpg_scan, const uint8_t *jpg_scan_end, uint8_t **jpg_offset, const uint32_t timestamp, const uint8_t *quantization_table_luminance, const uint8_t *quantization_table_chrominance);
private: private:
uint16_t width_, height_; const micro_rtsp_source& source_;
uint32_t ssrc_; uint32_t ssrc_;
uint16_t sequence_number_; uint16_t sequence_number_;
}; };

View File

@@ -1,33 +1,13 @@
#include <esp32-hal-log.h> #include <esp32-hal-log.h>
#include <iomanip>
#include <unordered_map>
#include <regex> #include <regex>
#include "micro_rtsp_requests.h" #include "micro_rtsp_requests.h"
// https://datatracker.ietf.org/doc/html/rfc2326 // https://datatracker.ietf.org/doc/html/rfc2326
micro_rtsp_requests::rtsp_command micro_rtsp_requests::parse_command(const std::string &request) const std::string micro_rtsp_requests::available_stream_name_ = "/mjpeg/1";
{
log_v("request: %s", request.c_str());
// Check for RTSP commands: Option, Describe, Setup, Play, Teardown
if (std::regex_match(request, std::regex("^OPTION ", std::regex_constants::icase)))
return rtsp_command::rtsp_command_option;
if (std::regex_match(request, std::regex("^DESCRIBE ", std::regex_constants::icase)))
return rtsp_command::rtsp_command_describe;
if (std::regex_match(request, std::regex("^SETUP ", std::regex_constants::icase)))
return rtsp_command::rtsp_command_setup;
if (std::regex_match(request, std::regex("^PLAY ", std::regex_constants::icase)))
return rtsp_command::rtsp_command_play;
if (std::regex_match(request, std::regex("^TEARDOWN ", std::regex_constants::icase)))
return rtsp_command::rtsp_command_teardown;
log_e("Invalid rtsp command: %s", request.c_str());
return rtsp_command::rtsp_command_unknown;
}
bool micro_rtsp_requests::parse_client_port(const std::string &request) bool micro_rtsp_requests::parse_client_port(const std::string &request)
{ {
@@ -41,189 +21,195 @@ bool micro_rtsp_requests::parse_client_port(const std::string &request)
return false; return false;
} }
client_port_ = std::stoi(match[1].str()); start_client_port_ = std::stoi(match[1].str());
return true; return true;
} }
bool micro_rtsp_requests::parse_cseq(const std::string &request) std::string micro_rtsp_requests::handle_rtsp_error(unsigned long cseq, unsigned short code, const std::string &message)
{ {
log_v("request: %s", request.c_str()); log_e("code: %d, message: %s", code, message.c_str());
auto now = time(nullptr);
// CSeq: 2
std::regex regex("CSeq: (\\d+)", std::regex_constants::icase);
std::smatch match;
if (!std::regex_match(request, match, regex))
{
log_e("CSeq not found");
return false;
}
cseq_ = std::stoul(match[1].str());
return true;
}
bool micro_rtsp_requests::parse_stream_url(const std::string &request)
{
log_v("request: %s", request.c_str());
// SETUP rtsp://192.168.10.93:1234/mjpeg/1 RTSP/1.0
std::regex regex("rtsp:\\/\\/([\\w.]+):(\\d+)\\/([\\/\\w]+)\\s+RTSP/1.0", std::regex_constants::icase);
std::smatch match;
if (!std::regex_match(request, match, regex))
{
log_e("Unable to parse url");
return false;
}
host_url_ = match[1].str();
host_port_ = std::stoi(match[2].str());
stream_name_ = match[3].str();
return true;
}
std::string micro_rtsp_requests::date_header()
{
char buffer[50];
auto now = std::time(nullptr);
std::strftime(buffer, sizeof(buffer), "Date: %a, %b %d %Y %H:%M:%S GMT", std::gmtime(&now));
return buffer;
}
std::string micro_rtsp_requests::rtsp_error(unsigned short code, const std::string &message)
{
log_v("code: %d, message: %s", code, message.c_str());
std::ostringstream oss; std::ostringstream oss;
oss << "RTSP/1.0 " << code << " " << message << "\r\n" oss << "RTSP/1.0 " << code << " " << message << "\r\n"
<< "CSeq: " << cseq_ << "\r\n" << "CSeq: " << cseq << "\r\n"
<< date_header() << "\r\n" << std::put_time(std::gmtime(&now), "Date: %a, %b %d %Y %H:%M:%S GMT") << "\r\n";
<< "\r\n";
return oss.str(); return oss.str();
} }
std::string micro_rtsp_requests::handle_option(const std::string &request) // OPTIONS rtsp://192.168.178.247:554/mjpeg/1 RTSP/1.0
// CSeq: 2
// User-Agent: LibVLC/3.0.20 (LIVE555 Streaming Media v2016.11.28)
std::string micro_rtsp_requests::handle_options(unsigned long cseq)
{ {
log_v("request: %s", request.c_str()); auto now = time(nullptr);
std::ostringstream oss; std::ostringstream oss;
oss << "RTSP/1.0 200 OK\r\n" oss << "RTSP/1.0 200 OK\r\n"
<< "CSeq: " << cseq_ << "\r\n" << "CSeq: " << cseq << "\r\n"
<< date_header() << "\r\n" << std::put_time(std::gmtime(&now), "Date: %a, %b %d %Y %H:%M:%S GMT") << "\r\n"
<< "Content-Length: 0\r\n" << "Content-Length: 0\r\n"
<< "Public: DESCRIBE, SETUP, TEARDOWN, PLAY, PAUSE\r\n" << "Public: DESCRIBE, SETUP, TEARDOWN, PLAY, PAUSE";
<< "\r\n";
return oss.str(); return oss.str();
} }
std::string micro_rtsp_requests::handle_describe(const std::string &request) // DESCRIBE rtsp://192.168.178.247:554/mjpeg/1 RTSP/1.0
// CSeq: 3
// User-Agent: LibVLC/3.0.20 (LIVE555 Streaming Media v2016.11.28)
// Accept: application/sdp
std::string micro_rtsp_requests::handle_describe(unsigned long cseq, const std::string &request)
{ {
log_v("request: %s", request.c_str()); // Parse the url
static const std::regex regex_url("rtsp:\\/\\/([^\\/:]+)(?::(\\d+))?(\\/.*)?\\s+RTSP\\/1\\.0", std::regex_constants::icase);
std::smatch match;
if (!std::regex_search(request, match, regex_url))
return handle_rtsp_error(cseq, 400, "Invalid URL");
if (!parse_stream_url(request)) auto host = match[1].str();
return rtsp_error(400, "Invalid Stream Name"); auto port = match[2].str().length() > 0 ? std::stoi(match[2].str()) : 554;
auto path = match[3].str();
log_i("host: %s, port: %d, path: %s", host.c_str(), port, path.c_str());
if (stream_name_ != available_stream_name_) if (path != available_stream_name_)
return rtsp_error(404, "Stream Not Found"); return handle_rtsp_error(cseq, 404, "Stream Not Found");
std::ostringstream sdpos; std::ostringstream osbody;
sdpos << "v=0\r\n" osbody << "v=0\r\n"
<< "o=- " << host_port_ << " 1 IN IP4 " << std::rand() << "\r\n" << "o=- " << std::rand() << " 1 IN IP4 " << host << "\r\n"
<< "s=\r\n" << "s=\r\n"
<< "t=0 0\r\n" // start / stop - 0 -> unbounded and permanent session << "t=0 0\r\n" // start / stop - 0 -> unbounded and permanent session
<< "m=video 0 RTP/AVP 26\r\n" // currently we just handle UDP sessions << "m=video 0 RTP/AVP 26\r\n" // currently we just handle UDP sessions
<< "c=IN IP4 0.0.0.0\r\n"; << "c=IN IP4 0.0.0.0\r\n";
auto sdp = sdpos.str(); auto body = osbody.str();
auto now = time(nullptr);
std::ostringstream oss; std::ostringstream oss;
oss << "RTSP/1.0 200 OK\r\n" oss << "RTSP/1.0 200 OK\r\n"
<< "CSeq: " << cseq_ << "\r\n" << "CSeq: " << cseq << "\r\n"
<< date_header() << "\r\n" << std::put_time(std::gmtime(&now), "Date: %a, %b %d %Y %H:%M:%S GMT") << "\r\n"
<< "Content-Base: " << stream_name_ << "/\r\n" << "Content-Base: rtsp://" << host << ":" << port << path << "\r\n"
<< "Content-Type: application/sdp\r\n" << "Content-Type: application/sdp\r\n"
<< "Content-Length: " << sdp.size() << "\r\n" << "Content-Length: " << body.size() << "\r\n"
<< "\r\n" << "\r\n"
<< sdp; << body;
return oss.str(); return oss.str();
} }
std::string micro_rtsp_requests::handle_setup(const std::string &request) // SETUP rtsp://192.168.178.247:554/mjpeg/1 RTSP/1.0
// CSeq: 0
// Transport: RTP/AVP;unicast;client_port=9058-9059
std::string micro_rtsp_requests::handle_setup(unsigned long cseq, const std::map<std::string, std::string> &lines)
{ {
log_v("request: %s", request.c_str()); log_v("request: %s", request.c_str());
tcp_transport_ = request.find("rtp/avp/tcp") != std::string::npos; auto it = lines.find("Transport");
if (it == lines.end())
return handle_rtsp_error(cseq, 400, "No Transport Header Found");
if (!parse_client_port(request)) static const std::regex regex_transport("\\s+RTP\\/AVP(\\/TCP)?;unicast;client_port=(\\d+)-(\\d+)", std::regex_constants::icase);
return rtsp_error(400, "Could Not Find Client Port"); std::smatch match;
if (!std::regex_search(it->second, match, regex_transport))
return handle_rtsp_error(cseq, 400, "Could Not Parse Transport");
tcp_transport_ = match[1].str().length() > 0;
start_client_port_ = std::stoi(match[2].str());
end_client_port_ = std::stoi(match[3].str());
log_i("tcp_transport: %d, start_client_port: %d, end_client_port: %d", tcp_transport_, start_client_port_, end_client_port_);
std::ostringstream ostransport; std::ostringstream ostransport;
if (tcp_transport_) if (tcp_transport_)
ostransport << "RTP/AVP/TCP;unicast;interleaved=0-1"; ostransport << "RTP/AVP/TCP;unicast;interleaved=0-1";
else else
ostransport << "RTP/AVP;unicast;destination=127.0.0.1;source=127.0.0.1;client_port=" << client_port_ << "-" << client_port_ + 1 << ";server_port=" << rtp_streamer_port_ << "-" << rtcp_streamer_port_; ostransport << "RTP/AVP;unicast;destination=127.0.0.1;source=127.0.0.1;client_port=" << start_client_port_ << "-" << end_client_port_ + 1 << ";server_port=" << rtp_streamer_port_ << "-" << rtcp_streamer_port_;
auto now = time(nullptr);
std::ostringstream oss; std::ostringstream oss;
oss << "RTSP/1.0 200 OK\r\n" oss << "RTSP/1.0 200 OK\r\n"
<< "CSeq: " << cseq_ << "\r\n" << "CSeq: " << cseq << "\r\n"
<< date_header() << "\r\n" << std::put_time(std::gmtime(&now), "Date: %a, %b %d %Y %H:%M:%S GMT") << "\r\n"
<< "Transport: " << ostransport.str() << "\r\n" << "Transport: " << ostransport.str() << "\r\n"
<< "Session: " << rtsp_session_id_ << "\r\n" << "Session: " << rtsp_session_id_;
<< "\r\n";
return oss.str(); return oss.str();
} }
std::string micro_rtsp_requests::handle_play(const std::string &request) std::string micro_rtsp_requests::handle_play(unsigned long cseq)
{ {
log_v("request: %s", request.c_str()); log_v("request: %s", request.c_str());
stream_active_ = true; stream_active_ = true;
auto now = time(nullptr);
std::ostringstream oss; std::ostringstream oss;
oss << "RTSP/1.0 200 OK\r\n" oss << "RTSP/1.0 200 OK\r\n"
<< "CSeq: " << cseq_ << "\r\n" << "CSeq: " << cseq << "\r\n"
<< date_header() << "\r\n" << std::put_time(std::gmtime(&now), "Date: %a, %b %d %Y %H:%M:%S GMT") << "\r\n"
<< "Range: npt=0.000-\r\n" << "Range: npt=0.000-\r\n"
<< "Session: " << rtsp_session_id_ << "\r\n" << "Session: " << rtsp_session_id_ << "\r\n"
<< "RTP-Info: url=rtsp://127.0.0.1:8554/" << available_stream_name_ << "/track1\r\n" << "RTP-Info: url=rtsp://127.0.0.1:8554" << available_stream_name_ << "/track1" << "\r\n"
<< "\r\n"; << "\r\n";
return oss.str(); return oss.str();
} }
std::string micro_rtsp_requests::handle_teardown(const std::string &request) std::string micro_rtsp_requests::handle_teardown(unsigned long cseq)
{ {
log_v("request: %s", request.c_str()); log_v("request: %s", request.c_str());
stream_stopped_ = true; stream_stopped_ = true;
auto now = time(nullptr);
std::ostringstream oss; std::ostringstream oss;
oss << "RTSP/1.0 200 OK\r\n" oss << "RTSP/1.0 200 OK\r\n"
<< "CSeq: " << cseq_ << "\r\n" << "CSeq: " << cseq << "\r\n"
<< date_header() << "\r\n" << std::put_time(std::gmtime(&now), "Date: %a, %b %d %Y %H:%M:%S GMT") << "\r\n";
<< "\r\n";
return oss.str(); return oss.str();
} }
// Parse a request e.g.
// Request: OPTIONS rtsp://192.168.178.247:554/mjpeg/1 RTSP/1.0
// CSeq: 2
// User-Agent: LibVLC/3.0.20 (LIVE555 Streaming Media v2016.11.28)
std::string micro_rtsp_requests::process_request(const std::string &request) std::string micro_rtsp_requests::process_request(const std::string &request)
{ {
log_v("request: %s", request.c_str()); log_v("request: %s", request.c_str());
auto command = parse_command(request); std::stringstream ss(request);
if (command != rtsp_command_unknown) // Get the request line
{ std::string request_line;
if (!parse_cseq(request)) if (!std::getline(ss, request_line))
return rtsp_error(400, "No Sequence Found"); return handle_rtsp_error(0, 400, "No Request Found");
switch (command) // Create a map with headers
std::string line;
std::map<std::string, std::string> headers;
std::size_t pos;
while (std::getline(ss, line))
{ {
case rtsp_command_option: if ((pos = line.find(':')) != std::string::npos)
return handle_option(request); headers[line.substr(0, pos)] = line.substr(pos + 1);
case rtsp_command_describe: else
return handle_describe(request); log_e("No : found for header: %s", line.c_str());
case rtsp_command_setup:
return handle_setup(request);
case rtsp_command_play:
return handle_play(request);
case rtsp_command_teardown:
return handle_teardown(request);
}
} }
return rtsp_error(400, "Unknown Command"); log_i("request_line: %s", request_line.c_str());
for (const auto &header : headers)
log_i("header: %s: %s", header.first.c_str(), header.second.c_str());
// Check for CSeq
const auto cseq_it = headers.find("CSeq");
if (cseq_it == headers.end())
return handle_rtsp_error(0, 400, "No Sequence Found");
auto cseq = std::stoul(cseq_it->second);
if (request_line.find("OPTIONS") == 0)
return handle_options(cseq);
if (request_line.find("DESCRIBE") == 0)
return handle_describe(cseq, request_line);
if (request_line.find("SETUP") == 0)
return handle_setup(cseq, headers);
if (request_line.find("PLAY") == 0)
return handle_play(cseq);
if (request_line.find("TEARDOWN") == 0)
return handle_teardown(cseq);
return handle_rtsp_error(cseq, 400, "Unknown Command or malformed request");
} }

View File

@@ -6,11 +6,9 @@
// Check client connections every 100 milliseconds // Check client connections every 100 milliseconds
#define CHECK_CLIENT_INTERVAL 10 #define CHECK_CLIENT_INTERVAL 10
micro_rtsp_server::micro_rtsp_server(micro_rtsp_camera &source, unsigned frame_interval /*= 100*/) micro_rtsp_server::micro_rtsp_server(micro_rtsp_source &source)
: source_(source), streamer_(source.width(), source.height()) : source_(source), streamer_(source)
{ {
log_v("frame_interval:%d", frame_interval);
frame_interval_ = frame_interval;
} }
micro_rtsp_server::~micro_rtsp_server() micro_rtsp_server::~micro_rtsp_server()
@@ -52,7 +50,7 @@ void micro_rtsp_server::loop()
if (next_frame_update_ < now) if (next_frame_update_ < now)
{ {
log_v("Stream frame"); log_v("Stream frame t=%d", next_frame_update_);
next_frame_update_ = now + frame_interval_; next_frame_update_ = now + frame_interval_;
auto ts = time(nullptr); auto ts = time(nullptr);
@@ -96,14 +94,15 @@ void micro_rtsp_server::rtsp_client::handle_request()
auto bytes_available = available(); auto bytes_available = available();
if (bytes_available > 0) if (bytes_available > 0)
{ {
std::string request; std::string request(bytes_available, '\0');
request.reserve(bytes_available); if (read((uint8_t*)&request[0], bytes_available) == bytes_available)
if (read((uint8_t *)request.data(), bytes_available) == bytes_available)
{ {
log_i("Request: %s", request); request.resize(bytes_available);
log_i("Request: %s", request.c_str());
auto response = process_request(request); auto response = process_request(request);
log_i("Response: %s", response); log_i("Response: %s", response.c_str());
write(response.data(), response.size()); println(response.c_str());
println();
} }
} }
} }

View File

@@ -5,11 +5,9 @@
#include "micro_rtsp_streamer.h" #include "micro_rtsp_streamer.h"
#include "esp_random.h" #include "esp_random.h"
micro_rtsp_streamer::micro_rtsp_streamer(const uint16_t width, const uint16_t height) micro_rtsp_streamer::micro_rtsp_streamer(const micro_rtsp_source &source)
: source_(source)
{ {
log_v("width:%d, height:%d", width, height);
width_ = width;
height_ = height;
// Random number // Random number
ssrc_ = esp_random(); ssrc_ = esp_random();
sequence_number_ = 0; sequence_number_ = 0;
@@ -52,8 +50,8 @@ rtp_over_tcp_hdr_t *micro_rtsp_streamer::create_jpg_packet(const uint8_t *jpg_sc
packet->jpeg_hdr.off = (uint32_t)(*jpg_offset - jpg_scan); // fragment byte offset (24 bits in jpg) packet->jpeg_hdr.off = (uint32_t)(*jpg_offset - jpg_scan); // fragment byte offset (24 bits in jpg)
packet->jpeg_hdr.type = 0; // id of jpeg decoder params packet->jpeg_hdr.type = 0; // id of jpeg decoder params
packet->jpeg_hdr.q = (uint8_t)(include_quantization_tables ? 0x80 : 0x5e); // quantization factor (or table id) 5eh=94d packet->jpeg_hdr.q = (uint8_t)(include_quantization_tables ? 0x80 : 0x5e); // quantization factor (or table id) 5eh=94d
packet->jpeg_hdr.width = (uint8_t)(width_ >> 3); // frame width in 8 pixel blocks packet->jpeg_hdr.width = (uint8_t)(source_.width() >> 3); // frame width in 8 pixel blocks
packet->jpeg_hdr.height = (uint8_t)(height_ >> 3); // frame height in 8 pixel blocks packet->jpeg_hdr.height = (uint8_t)(source_.height() >> 3); // frame height in 8 pixel blocks
log_v("jpeg_hdr={.tspec:%u,.off:0x%6x,.type:0x2%x,.q:%u,.width:%u.height:%u}", packet->jpeg_hdr.tspec, packet->jpeg_hdr.off, packet->jpeg_hdr.type, packet->jpeg_hdr.q, packet->jpeg_hdr.width, packet->jpeg_hdr.height); log_v("jpeg_hdr={.tspec:%u,.off:0x%6x,.type:0x2%x,.q:%u,.width:%u.height:%u}", packet->jpeg_hdr.tspec, packet->jpeg_hdr.off, packet->jpeg_hdr.type, packet->jpeg_hdr.q, packet->jpeg_hdr.width, packet->jpeg_hdr.height);
// Only in first packet of the frame // Only in first packet of the frame

View File

@@ -49,7 +49,7 @@ monitor_filters = esp32_exception_decoder
build_flags = build_flags =
-Ofast -Ofast
-D 'BOARD_NAME="${this.board}"' -D 'BOARD_NAME="${this.board}"'
-D 'CORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_VERBOSE' -D 'CORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_INFO'
-D 'IOTWEBCONF_PASSWORD_LEN=64' -D 'IOTWEBCONF_PASSWORD_LEN=64'
board_build.embed_txtfiles = board_build.embed_txtfiles =