Macros | Enumerations | Functions | Variables
webrtc.cpp File Reference
#include <gst/gst.h>
#include <gst/sdp/sdp.h>
#include <gst/app/app.h>
#include <gst/webrtc/webrtc.h>
#include <libsoup/soup.h>
#include <json-glib/json-glib.h>
#include <string.h>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <sensor_msgs/image_encodings.h>
#include <thread>
#include <std_msgs/String.h>
Include dependency graph for webrtc.cpp:

Go to the source code of this file.

Macros

#define GST_USE_UNSTABLE_API
 
#define RTP_CAPS_OPUS   "application/x-rtp,media=audio,encoding-name=OPUS,payload="
 
#define RTP_CAPS_VP8   "application/x-rtp,media=video,encoding-name=VP8,payload="
 
#define STUN_SERVER   " stun-server=stun://stun.l.google.com:19302 "
 

Enumerations

enum  AppState {
  APP_STATE_UNKNOWN = 0, APP_STATE_ERROR = 1, SERVER_CONNECTING = 1000, SERVER_CONNECTION_ERROR,
  SERVER_CONNECTED, SERVER_REGISTERING = 2000, SERVER_REGISTRATION_ERROR, SERVER_REGISTERED,
  SERVER_CLOSED, PEER_CONNECTING = 3000, PEER_CONNECTION_ERROR, PEER_CONNECTED,
  PEER_CALL_NEGOTIATING = 4000, PEER_CALL_STARTED, PEER_CALL_STOPPING, PEER_CALL_STOPPED,
  PEER_CALL_ERROR
}
 

Functions

static gboolean check_plugins (void)
 
static gboolean cleanup_and_quit_loop (const gchar *msg, AppState state)
 
static void connect_to_websocket_server_async (void)
 
static gchar * get_string_from_json_object (JsonObject *object)
 
GstCaps * gst_caps_new_from_image (const sensor_msgs::Image::ConstPtr &msg)
 
GstSample * gst_sample_new_from_image (const sensor_msgs::Image::ConstPtr &msg)
 
static void handle_media_stream (GstPad *pad, GstElement *pipe, const char *convert_name, const char *sink_name)
 
void image_cb (const sensor_msgs::Image::ConstPtr &msg)
 
int main (int argc, char **argv)
 
static void on_ice_gathering_state_notify (GstElement *webrtcbin, GParamSpec *pspec, gpointer user_data)
 
static void on_incoming_decodebin_stream (GstElement *decodebin, GstPad *pad, GstElement *pipe)
 
static void on_incoming_stream (GstElement *webrtc, GstPad *pad, GstElement *pipe)
 
static void on_negotiation_needed (GstElement *element, gpointer user_data)
 
static void on_offer_created (GstPromise *promise, gpointer user_data)
 
static void on_server_closed (SoupWebsocketConnection *conn G_GNUC_UNUSED, gpointer user_data G_GNUC_UNUSED)
 
static void on_server_connected (SoupSession *session, GAsyncResult *res, SoupMessage *msg)
 
static void on_server_message (SoupWebsocketConnection *conn, SoupWebsocketDataType type, GBytes *message, gpointer user_data)
 
static gboolean register_with_server (void)
 
static void send_ice_candidate_message (GstElement *webrtc G_GNUC_UNUSED, guint mlineindex, gchar *candidate, gpointer user_data G_GNUC_UNUSED)
 
static void send_sdp_to_peer (GstWebRTCSessionDescription *desc)
 
static gboolean setup_call (void)
 
static gboolean start_pipeline (void)
 
void startLoopAndConnect ()
 

Variables

static AppState app_state = APP_STATE_UNKNOWN
 
static GstElement * appsrc_
 
static const gchar * audio_device = nullptr
 
static gboolean disable_ssl = FALSE
 
static GOptionEntry entries []
 
image_transport::Subscriber image_sub_
 
std::unique_ptr< image_transport::ImageTransportimage_transport_
 
static GMainLoop * loop
 
std::thread loop_thread_
 
static const int MAXRETRIES = 5
 
static const gchar * peer_id = nullptr
 
static GstElement * pipe1
 
static GObject * receive_channel
 
static int retries = 0
 
static GObject * send_channel
 
static const gchar * server_url = "wss://127.0.0.1:8443"
 
gboolean serverConnected = FALSE
 
static GCancellable * serverConnection
 
gboolean serverConnectStarted = FALSE
 
static const gchar * turnserver_login = nullptr
 
static const gchar * turnserver_port = nullptr
 
static const gchar * video_bitrate = nullptr
 
static const gchar * video_height = nullptr
 
static const gchar * video_width = nullptr
 
static GstElement * webrtc1
 
static ros::Publisher webrtcstatus_pub
 
static SoupWebsocketConnection * ws_conn = nullptr
 

Macro Definition Documentation

#define GST_USE_UNSTABLE_API

Definition at line 10 of file webrtc.cpp.

#define RTP_CAPS_OPUS   "application/x-rtp,media=audio,encoding-name=OPUS,payload="

Definition at line 343 of file webrtc.cpp.

#define RTP_CAPS_VP8   "application/x-rtp,media=video,encoding-name=VP8,payload="

Definition at line 344 of file webrtc.cpp.

#define STUN_SERVER   " stun-server=stun://stun.l.google.com:19302 "

Definition at line 342 of file webrtc.cpp.

Enumeration Type Documentation

enum AppState
Enumerator
APP_STATE_UNKNOWN 
APP_STATE_ERROR 
SERVER_CONNECTING 
SERVER_CONNECTION_ERROR 
SERVER_CONNECTED 
SERVER_REGISTERING 
SERVER_REGISTRATION_ERROR 
SERVER_REGISTERED 
SERVER_CLOSED 
PEER_CONNECTING 
PEER_CONNECTION_ERROR 
PEER_CONNECTED 
PEER_CALL_NEGOTIATING 
PEER_CALL_STARTED 
PEER_CALL_STOPPING 
PEER_CALL_STOPPED 
PEER_CALL_ERROR 

Definition at line 25 of file webrtc.cpp.

Function Documentation

static gboolean check_plugins ( void  )
static

Definition at line 747 of file webrtc.cpp.

static gboolean cleanup_and_quit_loop ( const gchar *  msg,
AppState  state 
)
static

Definition at line 90 of file webrtc.cpp.

static void connect_to_websocket_server_async ( void  )
static

Definition at line 714 of file webrtc.cpp.

static gchar* get_string_from_json_object ( JsonObject *  object)
static

Definition at line 118 of file webrtc.cpp.

GstCaps* gst_caps_new_from_image ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 770 of file webrtc.cpp.

GstSample* gst_sample_new_from_image ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 805 of file webrtc.cpp.

static void handle_media_stream ( GstPad *  pad,
GstElement *  pipe,
const char *  convert_name,
const char *  sink_name 
)
static

Definition at line 137 of file webrtc.cpp.

void image_cb ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 846 of file webrtc.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 865 of file webrtc.cpp.

static void on_ice_gathering_state_notify ( GstElement *  webrtcbin,
GParamSpec *  pspec,
gpointer  user_data 
)
static

Definition at line 320 of file webrtc.cpp.

static void on_incoming_decodebin_stream ( GstElement *  decodebin,
GstPad *  pad,
GstElement *  pipe 
)
static

Definition at line 179 of file webrtc.cpp.

static void on_incoming_stream ( GstElement *  webrtc,
GstPad *  pad,
GstElement *  pipe 
)
static

Definition at line 204 of file webrtc.cpp.

static void on_negotiation_needed ( GstElement *  element,
gpointer  user_data 
)
static

Definition at line 310 of file webrtc.cpp.

static void on_offer_created ( GstPromise *  promise,
gpointer  user_data 
)
static

Definition at line 286 of file webrtc.cpp.

static void on_server_closed ( SoupWebsocketConnection *conn  G_GNUC_UNUSED,
gpointer user_data  G_GNUC_UNUSED 
)
static

Definition at line 511 of file webrtc.cpp.

static void on_server_connected ( SoupSession *  session,
GAsyncResult *  res,
SoupMessage *  msg 
)
static

Definition at line 680 of file webrtc.cpp.

static void on_server_message ( SoupWebsocketConnection *  conn,
SoupWebsocketDataType  type,
GBytes *  message,
gpointer  user_data 
)
static

Definition at line 525 of file webrtc.cpp.

static gboolean register_with_server ( void  )
static

Definition at line 488 of file webrtc.cpp.

static void send_ice_candidate_message ( GstElement *webrtc  G_GNUC_UNUSED,
guint  mlineindex,
gchar *  candidate,
gpointer user_data  G_GNUC_UNUSED 
)
static

Definition at line 224 of file webrtc.cpp.

static void send_sdp_to_peer ( GstWebRTCSessionDescription *  desc)
static

Definition at line 248 of file webrtc.cpp.

static gboolean setup_call ( void  )
static

Definition at line 468 of file webrtc.cpp.

static gboolean start_pipeline ( void  )
static

Definition at line 346 of file webrtc.cpp.

void startLoopAndConnect ( )

Definition at line 829 of file webrtc.cpp.

Variable Documentation

AppState app_state = APP_STATE_UNKNOWN
static

Definition at line 53 of file webrtc.cpp.

GstElement * appsrc_
static

Definition at line 49 of file webrtc.cpp.

const gchar* audio_device = nullptr
static

Definition at line 67 of file webrtc.cpp.

gboolean disable_ssl = FALSE
static

Definition at line 56 of file webrtc.cpp.

GOptionEntry entries[]
static
Initial value:
=
{
{ "peer-id", 0, 0, G_OPTION_ARG_STRING, &peer_id, "String ID of the peer to connect to", "ID" },
{ "server", 0, 0, G_OPTION_ARG_STRING, &server_url, "Signalling server to connect to", "URL" },
{ "disable-ssl", 0, 0, G_OPTION_ARG_NONE, &disable_ssl, "Disable ssl", NULL },
{ "audio-device", 0, 0, G_OPTION_ARG_STRING, &audio_device, "String of the audio device number", "ID" },
{ "video-width", 0, 0, G_OPTION_ARG_STRING, &video_width, "video width pixels", NULL },
{ "video-height", 0, 0, G_OPTION_ARG_STRING, &video_height, "video height pixels", NULL },
{ "video-bitrate", 0, 0, G_OPTION_ARG_STRING, &video_bitrate, "target bitrate kbps", NULL },
{ "turnserver-port", 0, 0, G_OPTION_ARG_STRING, &turnserver_port, "TURN server port number", NULL },
{ "turnserver-login", 0, 0, G_OPTION_ARG_STRING, &turnserver_login, "TURN server user:pass", NULL },
{ NULL },
}
static const gchar * video_height
Definition: webrtc.cpp:69
static const gchar * video_bitrate
Definition: webrtc.cpp:70
static const gchar * video_width
Definition: webrtc.cpp:68
static const gchar * turnserver_port
Definition: webrtc.cpp:72
static gboolean disable_ssl
Definition: webrtc.cpp:56
static const gchar * turnserver_login
Definition: webrtc.cpp:71
static const gchar * server_url
Definition: webrtc.cpp:55
static const gchar * audio_device
Definition: webrtc.cpp:67
static const gchar * peer_id
Definition: webrtc.cpp:54

Definition at line 75 of file webrtc.cpp.

Definition at line 60 of file webrtc.cpp.

std::unique_ptr<image_transport::ImageTransport> image_transport_

Definition at line 59 of file webrtc.cpp.

GMainLoop* loop
static

Definition at line 48 of file webrtc.cpp.

std::thread loop_thread_

Definition at line 62 of file webrtc.cpp.

const int MAXRETRIES = 5
static

Definition at line 64 of file webrtc.cpp.

const gchar* peer_id = nullptr
static

Definition at line 54 of file webrtc.cpp.

GstElement* pipe1
static

Definition at line 49 of file webrtc.cpp.

GObject * receive_channel
static

Definition at line 50 of file webrtc.cpp.

int retries = 0
static

Definition at line 63 of file webrtc.cpp.

GObject* send_channel
static

Definition at line 50 of file webrtc.cpp.

const gchar* server_url = "wss://127.0.0.1:8443"
static

Definition at line 55 of file webrtc.cpp.

gboolean serverConnected = FALSE

Definition at line 65 of file webrtc.cpp.

GCancellable* serverConnection
static

Definition at line 61 of file webrtc.cpp.

gboolean serverConnectStarted = FALSE

Definition at line 66 of file webrtc.cpp.

const gchar* turnserver_login = nullptr
static

Definition at line 71 of file webrtc.cpp.

const gchar* turnserver_port = nullptr
static

Definition at line 72 of file webrtc.cpp.

const gchar* video_bitrate = nullptr
static

Definition at line 70 of file webrtc.cpp.

const gchar* video_height = nullptr
static

Definition at line 69 of file webrtc.cpp.

const gchar* video_width = nullptr
static

Definition at line 68 of file webrtc.cpp.

GstElement * webrtc1
static

Definition at line 49 of file webrtc.cpp.

ros::Publisher webrtcstatus_pub
static

Definition at line 73 of file webrtc.cpp.

SoupWebsocketConnection* ws_conn = nullptr
static

Definition at line 52 of file webrtc.cpp.



oculusprime
Author(s): Colin Adamson
autogenerated on Wed Mar 10 2021 03:14:59