RsRtspClient.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2020 Intel Corporation. All Rights Reserved.
3 
4 #include "liveMedia.hh"
5 
6 #include "RsRtspClient.h"
7 #include <RsUsageEnvironment.h>
9 
10 #include <algorithm>
11 #include <iostream>
12 #include <math.h>
13 #include <string>
14 #include <thread>
15 #include <vector>
16 
17 #define RTSP_CLIENT_VERBOSITY_LEVEL 0 // by default, print verbose output from each "RTSPClient"
18 #define REQUEST_STREAMING_OVER_TCP 0
19 
20 // map for stream pysical sensor
21 // key is generated by rs2_stream+index: depth=1,color=2,irl=3,irr=4
22 std::map<std::pair<int, int>, rs2_extrinsics> minimal_extrinsics_map;
23 
25 {
26  return std::string("[" + function + "] error: " + retVal.msg + " - " + std::to_string(retVal.exit_code));
27 }
28 
30 {
31  long long int key;
32  key = t_profile.type * pow(10, 12) + t_profile.fmt * pow(10, 10) + t_profile.fps * pow(10, 8) + t_profile.index + t_profile.width * pow(10, 4) + t_profile.height;
33  return key;
34 }
35 
36 int RsRTSPClient::getPhysicalSensorUniqueKey(rs2_stream stream_type, int sensors_index)
37 {
38  return stream_type * 10 + sensors_index;
39 }
40 
41 IRsRtsp *RsRTSPClient::createNew(char const *t_rtspURL, char const *t_applicationName, portNumBits t_tunnelOverHTTPPortNum, int idx)
42 {
43  TaskScheduler *scheduler = BasicTaskScheduler::createNew();
44  UsageEnvironment *env = RSUsageEnvironment::createNew(*scheduler);
45 
46  RTSPClient::responseBufferSize = 100000;
47  return (IRsRtsp *)new RsRTSPClient(scheduler, env, t_rtspURL, RTSP_CLIENT_VERBOSITY_LEVEL, t_applicationName, t_tunnelOverHTTPPortNum, idx);
48 }
49 
50 RsRTSPClient::RsRTSPClient(TaskScheduler *t_scheduler, UsageEnvironment *t_env, char const *t_rtspURL, int t_verbosityLevel, char const *t_applicationName, portNumBits t_tunnelOverHTTPPortNum, int idx)
51  : RTSPClient(*t_env, t_rtspURL, t_verbosityLevel, t_applicationName, t_tunnelOverHTTPPortNum, -1)
52 {
54  m_env = t_env;
55  m_scheduler = t_scheduler;
56  m_idx = idx;
57 }
58 
60 
62 
63 std::vector<rs2_video_stream> RsRTSPClient::getStreams()
64 {
65  if (g_sdp[m_idx].size() == 0)
66  {
67  this->sendDescribeCommand(this->continueAfterDESCRIBE);
68  }
69  else
70  {
71  char* buf = strdup(g_sdp[m_idx].c_str());
72  this->continueAfterDESCRIBE(this, 0, buf);
73  }
74 
75  // wait for continueAfterDESCRIBE to finish
76  std::unique_lock<std::mutex> lck(m_commandMtx);
77  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
78  // for the next command - if not done - throw timeout
79  if (!m_commandDone)
80  {
81  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
82  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
83  }
84  m_commandDone = false;
85 
87  {
88  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
89  }
90 
91  if (this->m_supportedProfiles.size() == 0)
92  {
93  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_GENERAL, std::string("failed to get streams from network device at url: " + std::string(this->url()))};
94  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
95  }
96 
97  return this->m_supportedProfiles;
98 }
99 
101 {
102  long long int uniqueKey = getStreamProfileUniqueKey(t_stream);
103  RsMediaSubsession *subsession = this->m_subsessionMap.find(uniqueKey)->second;
104  if (subsession == nullptr)
105  {
106  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_WRONG_FLOW, "requested stream was not found"};
107  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
108  }
109 
110  if (!subsession->initiate())
111  {
112  this->envir() << "Failed to initiate the subsession \n";
113  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_WRONG_FLOW, "Failed to initiate the subsession"};
114  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
115  }
116 
117  // Continue setting up this subsession, by sending a RTSP "SETUP" command:
118  unsigned res = this->sendSetupCommand(*subsession, this->continueAfterSETUP, False, REQUEST_STREAMING_OVER_TCP);
119  // wait for continueAfterSETUP to finish
120  std::unique_lock<std::mutex> lck(m_commandMtx);
121  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
122  // for the next command
123  if (!m_commandDone)
124  {
125  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
126  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
127  }
128  m_commandDone = false;
129 
131  {
132  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
133  }
134 
135  subsession->sink = RsSink::createNew(this->envir(), *subsession, t_stream, m_memPool, this->url());
136  // perhaps use your own custom "MediaSink" subclass instead
137  if (subsession->sink == NULL)
138  {
139  this->envir() << "Failed to create a data sink for the subsession: " << this->envir().getResultMsg() << "\n";
140  RsRtspReturnValue err = {(RsRtspReturnCode)envir().getErrno(), std::string("Failed to create a data sink for the subsession: " + std::string(envir().getResultMsg()))};
141  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
142  }
143 
144  subsession->miscPtr = this; // a hack to let subsession handler functions get the "RTSPClient" from the subsession
145  ((RsSink *)(subsession->sink))->setCallback(t_callbackObj);
146  subsession->sink->startPlaying(*(subsession->readSource()), subsessionAfterPlaying, subsession);
147  // Also set a handler to be called if a RTCP "BYE" arrives for this subsession:
148  if (subsession->rtcpInstance() != NULL)
149  {
150  subsession->rtcpInstance()->setByeWithReasonHandler(subsessionByeHandler, subsession);
151  }
152 
153  return this->m_lastReturnValue.exit_code;
154 }
155 
157 {
158  unsigned res = this->sendPlayCommand(*this->m_scs.m_session, this->continueAfterPLAY);
159  // wait for continueAfterPLAY to finish
160  std::unique_lock<std::mutex> lck(m_commandMtx);
161  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
162  // for the next command
163  if (!m_commandDone)
164  {
165  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
166  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
167  }
168  m_commandDone = false;
169 
171  {
172  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
173  }
175 }
176 
178 {
179  unsigned res = this->sendPauseCommand(*this->m_scs.m_session, this->continueAfterPAUSE);
180  // wait for continueAfterPAUSE to finish
181  std::unique_lock<std::mutex> lck(m_commandMtx);
182  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
183  // for the next command
184  if (!m_commandDone)
185  {
186  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
187  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
188  }
189  m_commandDone = false;
191  {
192  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
193  }
195 }
196 
198 {
199  {
200  unsigned res = this->sendTeardownCommand(*this->m_scs.m_session, this->continueAfterTEARDOWN);
201  // wait for continueAfterTEARDOWN to finish
202  std::unique_lock<std::mutex> lck(m_commandMtx);
203  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
204  // for the next command
205  if (!m_commandDone)
206  {
207  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
208  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
209  }
210  m_commandDone = false;
211 
213  {
214  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
215  }
216  }
218  {
219  std::lock_guard<std::mutex> lk(m_taskSchedulerMutex);
220  }
221  this->envir() << "Closing the stream.\n";
222  UsageEnvironment *env = m_env;
223  TaskScheduler *scheduler = m_scheduler;
224  Medium::close(this);
225  env->reclaim();
226  delete scheduler;
228 }
229 
230 int RsRTSPClient::setOption(const std::string &t_sensorName, rs2_option t_option, float t_value)
231 {
232  std::string option = t_sensorName + "_" + std::to_string(t_option);
233  std::string value = std::to_string(t_value);
234  if (isActiveSession)
235  {
236  RTSPClient::sendSetParameterCommand(*this->m_scs.m_session, this->continueAfterSETCOMMAND, option.c_str(), value.c_str());
237  }
238  else
239  {
240  sendSetParameterCommand(this->continueAfterSETCOMMAND, option.c_str(), value.c_str());
241  }
242 
243  std::unique_lock<std::mutex> lck(m_commandMtx);
244  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
245  // for the next command
246  if (!m_commandDone)
247  {
248  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
249  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
250  }
251  m_commandDone = false;
252 
254  {
255  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
256  }
257 
259 }
260 
262 {
263  m_getParamRes = t_res;
264 }
265 
266 int RsRTSPClient::getOption(const std::string &t_sensorName, rs2_option t_option, float &t_value)
267 {
268  unsigned res;
269  t_value = m_getParamRes = -1;
270  std::string option = t_sensorName + "_" + std::to_string(t_option);
271  if (isActiveSession)
272  {
273  res = RTSPClient::sendGetParameterCommand(*this->m_scs.m_session, this->continueAfterGETCOMMAND, option.c_str());
274  }
275  else
276  {
277  res = sendGetParameterCommand(this->continueAfterGETCOMMAND, option.c_str());
278  }
279  // wait for continueAfterGETCOMMAND to finish
280  std::unique_lock<std::mutex> lck(m_commandMtx);
281  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
282  if (!m_commandDone)
283  {
284  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
285 
286  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
287  }
288  m_commandDone = false;
290  {
291  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
292  }
293 
294  t_value = m_getParamRes;
295 
297 }
298 
299 void schedulerThread(RsRTSPClient *t_rtspClientInstance)
300 {
301  std::unique_lock<std::mutex> lk(t_rtspClientInstance->getTaskSchedulerMutex());
302  t_rtspClientInstance->envir().taskScheduler().doEventLoop(&t_rtspClientInstance->getEventLoopWatchVariable());
303  lk.unlock();
304 }
305 
307 {
308  std::thread thread_scheduler(schedulerThread, this);
309  thread_scheduler.detach();
310  m_memPool = t_pool;
311 }
312 
314 {
315  m_deviceData = t_data;
316 }
317 std::vector<IpDeviceControlData> controls;
318 
319 std::vector<IpDeviceControlData> RsRTSPClient::getControls()
320 {
321  this->sendOptionsCommand(this->continueAfterOPTIONS);
322 
323  // wait for continueAfterOPTIONS to finish
324  std::unique_lock<std::mutex> lck(m_commandMtx);
325  m_cv.wait_for(lck, std::chrono::seconds(RTSP_CLIENT_COMMANDS_TIMEOUT_SEC), [this] { return m_commandDone; });
326  // for the next command
327  if (!m_commandDone)
328  {
329  RsRtspReturnValue err = {RsRtspReturnCode::ERROR_TIME_OUT, "client time out"};
330  throw std::runtime_error(format_error_msg(__FUNCTION__, err));
331  }
332  m_commandDone = false;
333 
335  {
336  throw std::runtime_error(format_error_msg(__FUNCTION__, m_lastReturnValue));
337  }
338  return controls;
339 }
340 
341 void updateExtrinsicsMap(rs2_video_stream videoStream, std::string extrinsics_str)
342 {
343  std::istringstream extrinsics_stream(extrinsics_str);
344  std::string s;
345  while (std::getline(extrinsics_stream, s, '&'))
346  {
348  int target_sensor;
349  int params_count = sscanf(s.c_str(),
350  "<to_sensor_%d>rotation:%f,%f,%f,%f,%f,%f,%f,%f,%ftranslation:%f,%f,%f",
351  &target_sensor,
352  &extrinsics.rotation[0],
353  &extrinsics.rotation[1],
354  &extrinsics.rotation[2],
355  &extrinsics.rotation[3],
356  &extrinsics.rotation[4],
357  &extrinsics.rotation[5],
358  &extrinsics.rotation[6],
359  &extrinsics.rotation[7],
360  &extrinsics.rotation[8],
361  &extrinsics.translation[0],
362  &extrinsics.translation[1],
363  &extrinsics.translation[2]);
364 
365  // hanle NaN values
366  if (params_count != SDP_EXTRINSICS_ARGS)
367  {
368  extrinsics = {{NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN}, {NAN, NAN, NAN}};
369  }
370 
371  minimal_extrinsics_map[std::make_pair(RsRTSPClient::getPhysicalSensorUniqueKey(videoStream.type, videoStream.index), target_sensor)] = extrinsics;
372  }
373 }
374 
375 /*********************************
376  * CALLBACKS *
377  *********************************/
378 
379 void RsRTSPClient::continueAfterDESCRIBE(RTSPClient *rtspClient, int resultCode, char *resultString)
380 {
381  std::string resultStr;
382  if (nullptr != resultString)
383  {
384  resultStr = resultString;
385  delete[] resultString;
386  }
387  UsageEnvironment &env = rtspClient->envir(); // alias
388  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
389  StreamClientState &scs = rsRtspClient->m_scs; // alias
390 
391  if (!resultStr.empty())
392  rsRtspClient->m_lastReturnValue.msg = resultStr;
393  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
394 
395  do
396  {
397  if (resultCode != 0)
398  {
399  env << "Failed to get a SDP description: " << resultStr.c_str() << "\n";
400  break;
401  }
402 
403  g_sdp[rsRtspClient->m_idx] = resultStr;
404 
405  // Create a media session object from this SDP description(resultString):
406  scs.m_session = RsMediaSession::createNew(env, resultStr.c_str());
407  if (scs.m_session == NULL)
408  {
409  env << "Failed to create a RsMediaSession object from the SDP description: " << env.getResultMsg() << "\n";
410  break;
411  }
412  else if (!scs.m_session->hasSubsessions())
413  {
414  env << "This session has no media subsessions (i.e., no \"m=\" lines)\n";
415  break;
416  }
417 
419  RsMediaSubsession *subsession = iter.next();
420  while (subsession != NULL)
421  {
422  // Get more data from the SDP string
423  const char *strWidthVal = subsession->attrVal_str("width");
424  const char *strHeightVal = subsession->attrVal_str("height");
425  const char *strFormatVal = subsession->attrVal_str("format");
426  const char *strUidVal = subsession->attrVal_str("uid");
427  const char *strFpsVal = subsession->attrVal_str("fps");
428  const char *strIndexVal = subsession->attrVal_str("stream_index");
429  const char *strStreamTypeVal = subsession->attrVal_str("stream_type");
430  const char *strBppVal = subsession->attrVal_str("bpp");
431 
432  const char *strSerialNumVal = subsession->attrVal_str("cam_serial_num");
433  const char *strCamNameVal = subsession->attrVal_str("cam_name");
434  const char *strUsbTypeVal = subsession->attrVal_str("usb_type");
435 
436  int width = strWidthVal != "" ? std::stoi(strWidthVal) : 0;
437  int height = strHeightVal != "" ? std::stoi(strHeightVal) : 0;
438  int format = strFormatVal != "" ? std::stoi(strFormatVal) : 0;
439  int uid = strUidVal != "" ? std::stoi(strUidVal) : 0;
440  int fps = strFpsVal != "" ? std::stoi(strFpsVal) : 0;
441  int index = strIndexVal != "" ? std::stoi(strIndexVal) : 0;
442  int stream_type = strStreamTypeVal != "" ? std::stoi(strStreamTypeVal) : 0;
443  int bpp = strBppVal != "" ? std::stoi(strBppVal) : 0;
444  rs2_video_stream videoStream;
445  videoStream.width = width;
446  videoStream.height = height;
447  videoStream.uid = uid;
448  videoStream.fmt = static_cast<rs2_format>(format);
449  videoStream.fps = fps;
450  videoStream.index = index;
451  videoStream.type = static_cast<rs2_stream>(stream_type);
452  videoStream.bpp = bpp;
453 
454  // intrinsics desirialization should happend at once (usgin json?)
455  videoStream.intrinsics.width = subsession->attrVal_int("width");
456  videoStream.intrinsics.height = subsession->attrVal_int("height");
457  videoStream.intrinsics.ppx = subsession->attrVal_int("ppx");
458  videoStream.intrinsics.ppy = subsession->attrVal_int("ppy");
459  videoStream.intrinsics.fx = subsession->attrVal_int("fx");
460  videoStream.intrinsics.fy = subsession->attrVal_int("fy");
461  CompressionFactory::getIsEnabled() = subsession->attrVal_bool("compression");
462  videoStream.intrinsics.model = (rs2_distortion)subsession->attrVal_int("model");
463 
464  for (size_t i = 0; i < 5; i++)
465  {
466  videoStream.intrinsics.coeffs[i] = subsession->attrVal_int("coeff_" + i);
467  }
468 
469  // extrinsics
470  std::string extrinsics = subsession->attrVal_str("extrinsics");
471  updateExtrinsicsMap(videoStream, extrinsics);
472 
473  DeviceData deviceData;
474  deviceData.serialNum = strSerialNumVal;
475  deviceData.name = strCamNameVal;
476  // Return spaces back to string after getting it from the SDP
477  std::replace(deviceData.name.begin(), deviceData.name.end(), '^', ' ');
478  deviceData.usbType = strUsbTypeVal;
479  rsRtspClient->setDeviceData(deviceData);
480 
481  long long int uniqueKey = getStreamProfileUniqueKey(videoStream);
482  rsRtspClient->m_subsessionMap.insert(std::pair<long long int, RsMediaSubsession *>(uniqueKey, subsession));
483  rsRtspClient->m_supportedProfiles.push_back(videoStream);
484  subsession = iter.next();
485  // TODO: when to delete p?
486  }
487  } while (0);
488 
489  {
490  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
491  rsRtspClient->m_commandDone = true;
492  }
493  rsRtspClient->m_cv.notify_one();
494 }
495 
496 void RsRTSPClient::continueAfterSETUP(RTSPClient *rtspClient, int resultCode, char *resultString)
497 {
498  std::string resultStr;
499  if (nullptr != resultString)
500  {
501  resultStr = resultString;
502  delete[] resultString;
503  }
504  UsageEnvironment &env = rtspClient->envir(); // alias
505  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
506  StreamClientState &scs = rsRtspClient->m_scs; // alias
507 
508  env << "continueAfterSETUP " << resultCode << " " << resultStr.c_str() << "\n";
509 
510  if (!resultStr.empty())
511  rsRtspClient->m_lastReturnValue.msg = resultStr;
512 
513  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
514  {
515  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
516  rsRtspClient->m_commandDone = true;
517  }
518  rsRtspClient->m_cv.notify_one();
519 }
520 
521 void RsRTSPClient::continueAfterPLAY(RTSPClient *rtspClient, int resultCode, char *resultString)
522 {
523  std::string resultStr;
524  if (nullptr != resultString)
525  {
526  resultStr = resultString;
527  delete[] resultString;
528  }
529  UsageEnvironment &env = rtspClient->envir(); // alias
530  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
531  env << "continueAfterPLAY " << resultCode << " " << resultStr.c_str() << "\n";
532 
533  if (!resultStr.empty())
534  rsRtspClient->m_lastReturnValue.msg = resultStr;
535  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
536 
537  {
538  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
539  rsRtspClient->m_commandDone = true;
540  }
541  rsRtspClient->m_cv.notify_one();
542 }
543 
544 void RsRTSPClient::continueAfterTEARDOWN(RTSPClient *rtspClient, int resultCode, char *resultString)
545 {
546  std::string resultStr;
547  if (nullptr != resultString)
548  {
549  resultStr = resultString;
550  delete[] resultString;
551  }
552  UsageEnvironment &env = rtspClient->envir(); // alias
553  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
554  env << "continueAfterTEARDOWN " << resultCode << " " << resultStr.c_str() << "\n";
555 
556  if (!resultStr.empty())
557  rsRtspClient->m_lastReturnValue.msg = resultStr;
558  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
559 
560  {
561  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
562  rsRtspClient->m_commandDone = true;
563  }
564  rsRtspClient->m_cv.notify_one();
565 }
566 
567 void RsRTSPClient::continueAfterPAUSE(RTSPClient *rtspClient, int resultCode, char *resultString)
568 {
569  std::string resultStr;
570  if (nullptr != resultString)
571  {
572  resultStr = resultString;
573  delete[] resultString;
574  }
575  UsageEnvironment &env = rtspClient->envir(); // alias
576  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
577  env << "continueAfterPAUSE " << resultCode << " " << resultStr.c_str() << "\n";
578 
579  if (!resultStr.empty())
580  rsRtspClient->m_lastReturnValue.msg = resultStr;
581  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
582 
583  {
584  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
585  rsRtspClient->m_commandDone = true;
586  }
587  rsRtspClient->m_cv.notify_one();
588 }
589 
590 void RsRTSPClient::continueAfterOPTIONS(RTSPClient *rtspClient, int resultCode, char *resultString)
591 {
592  std::string resultStr;
593  if (nullptr != resultString)
594  {
595  resultStr = resultString;
596  delete[] resultString;
597  }
598  UsageEnvironment &env = rtspClient->envir(); // alias
599  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
600  env << "continueAfterOPTIONS " << resultCode << " " << resultStr.c_str() << "\n";
601 
602  if (!resultStr.empty())
603  rsRtspClient->m_lastReturnValue.msg = resultStr;
604  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
605 
606  {
607  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
608  std::size_t foundBegin = resultStr.find_first_of("[");
609  IpDeviceControlData controlData;
610  int counter = 0;
611  while (foundBegin != std::string::npos)
612  {
613 
614  std::size_t foundEnd = resultStr.find_first_of("]", foundBegin + 1);
615  std::string controlsPerSensor = resultStr.substr(foundBegin + 1, foundEnd - foundBegin);
616  std::size_t pos = 0;
617  while ((pos = controlsPerSensor.find(';')) != std::string::npos)
618  {
619  std::string controlStr = controlsPerSensor.substr(0, pos);
620 
621  controlData.sensorId = counter == 0 ? 1 : 0;
622  int option_code;
623  int params_count = sscanf(controlStr.c_str(), "%d{%f,%f,%f,%f}", &option_code, &controlData.range.min, &controlData.range.max, &controlData.range.def, &controlData.range.step);
624 
625  //to avoid sscanf warning
626  controlData.option = (rs2_option)option_code;
627  controls.push_back(controlData);
628  controlsPerSensor.erase(0, pos + 1);
629  }
630  counter++;
631  foundBegin = resultStr.find_first_of("[", foundBegin + 1);
632  }
633  rsRtspClient->m_commandDone = true;
634  }
635  rsRtspClient->m_cv.notify_one();
636 }
637 
638 void RsRTSPClient::continueAfterSETCOMMAND(RTSPClient *rtspClient, int resultCode, char *resultString)
639 {
640  std::string resultStr;
641  if (nullptr != resultString)
642  {
643  resultStr = resultString;
644  delete[] resultString;
645  }
646  UsageEnvironment &env = rtspClient->envir(); // alias
647  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
648  env << "continueAfterSETCOMMAND " << resultCode << "\n";
649 
650  if (!resultStr.empty())
651  {
652  rsRtspClient->m_lastReturnValue.msg = resultStr;
653  }
654  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
655 
656  {
657  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
658  rsRtspClient->m_commandDone = true;
659  }
660  rsRtspClient->m_cv.notify_one();
661 }
662 
663 void RsRTSPClient::continueAfterGETCOMMAND(RTSPClient *rtspClient, int resultCode, char *resultString)
664 {
665  std::string resultStr;
666  if (nullptr != resultString)
667  {
668  resultStr = resultString;
669  delete[] resultString;
670  }
671  UsageEnvironment &env = rtspClient->envir(); // alias
672  RsRTSPClient *rsRtspClient = dynamic_cast<RsRTSPClient *>(rtspClient); // alias
673  DBG << "continueAfterGETCOMMAND: resultCode " << resultCode << ", resultString '" << resultStr.c_str();
674 
675  if (!resultStr.empty())
676  {
677  rsRtspClient->m_lastReturnValue.msg = resultStr;
678  }
679  rsRtspClient->m_lastReturnValue.exit_code = (RsRtspReturnCode)resultCode;
680 
681  if (resultCode == 0)
682  {
683  rsRtspClient->setGetParamResponse(std::stof(resultStr));
684  }
685 
686  {
687  std::lock_guard<std::mutex> lck(rsRtspClient->m_commandMtx);
688  rsRtspClient->m_commandDone = true;
689  }
690  rsRtspClient->m_cv.notify_one();
691 }
692 
693 // TODO: implementation
695 {
696  MediaSubsession *subsession = (MediaSubsession *)clientData;
697  RTSPClient *rtspClient = (RTSPClient *)(subsession->miscPtr);
698  rtspClient->envir() << "subsessionAfterPlaying\n";
699 }
700 
701 void RsRTSPClient::subsessionByeHandler(void *clientData, char const *reason) {}
702 
703 unsigned RsRTSPClient::sendSetParameterCommand(responseHandler *responseHandler, char const *parameterName, char const *parameterValue, Authenticator *authenticator)
704 {
705  if (fCurrentAuthenticator < authenticator)
706  fCurrentAuthenticator = *authenticator;
707  char *paramString = new char[strlen(parameterName) + strlen(parameterValue) + 10];
708  sprintf(paramString, "%s: %s\r\n", parameterName, parameterValue);
709  unsigned result = sendRequest(new RequestRecord(++fCSeq, "SET_PARAMETER", responseHandler, NULL, NULL, False, 0.0f, -1.0f, 1.0f, paramString));
710  delete[] paramString;
711  return result;
712 }
713 
714 unsigned RsRTSPClient::sendGetParameterCommand(responseHandler *responseHandler, char const *parameterName, Authenticator *authenticator)
715 {
716  if (fCurrentAuthenticator < authenticator)
717  fCurrentAuthenticator = *authenticator;
718 
719  // We assume that:
720  // parameterName is NULL means: Send no body in the request.
721  // parameterName is "" means: Send only \r\n in the request body.
722  // parameterName is non-empty means: Send "<parameterName>\r\n" as the request body.
723  unsigned parameterNameLen = parameterName == NULL ? 0 : strlen(parameterName);
724  char *paramString = new char[parameterNameLen + 3]; // the 3 is for \r\n + the '\0' byte
725  if (parameterName == NULL)
726  {
727  paramString[0] = '\0';
728  }
729  else
730  {
731  sprintf(paramString, "%s\r\n", parameterName);
732  }
733  unsigned result = sendRequest(new RequestRecord(++fCSeq, "GET_PARAMETER", responseHandler, NULL, NULL, False, 0.0f, -1.0f, 1.0f, paramString));
734  delete[] paramString;
735  return result;
736 }
737 
738 Boolean RsRTSPClient::setRequestFields(RequestRecord *request, char *&cmdURL, Boolean &cmdURLWasAllocated, char const *&protocolStr, char *&extraHeaders, Boolean &extraHeadersWereAllocated)
739 {
740  // Set various fields that will appear in our outgoing request, depending upon the particular command that we are sending.
741  if (request == nullptr)
742  {
743  return False;
744  }
745  if ((strcmp(request->commandName(), "SET_PARAMETER") == 0 || strcmp(request->commandName(), "GET_PARAMETER") == 0) && (request->session() == NULL))
746  {
747  cmdURL = new char[4];
748 
749  cmdURLWasAllocated = True; //use BaseUrl
750  sprintf(cmdURL, "%s", "*");
751  }
752  else
753  {
754  return RTSPClient::setRequestFields(request, cmdURL, cmdURLWasAllocated, protocolStr, extraHeaders, extraHeadersWereAllocated);
755  }
756 
757  return True;
758 }
static int getPhysicalSensorUniqueKey(rs2_stream stream_type, int sensors_index)
virtual int close()
rs2_format fmt
Definition: rs_internal.h:50
virtual int stop()
std::vector< rs2_video_stream > m_supportedProfiles
Definition: RsRtspClient.h:84
std::string serialNum
Definition: IRsRtsp.h:16
float stof(const std::string &value)
RsRtspReturnCode exit_code
Definition: RsRtspCommon.h:17
std::istringstream istringstream
Definition: Arg.h:43
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
Definition: extrinsics.h:59
virtual std::vector< IpDeviceControlData > getControls()
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
std::string g_sdp[2]
GLdouble s
std::mutex m_taskSchedulerMutex
Definition: RsRtspClient.h:98
TaskScheduler * m_scheduler
Definition: RsRtspClient.h:95
rs2_option option
Definition: RsCommon.h:39
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
Definition: rs_types.h:45
float translation[3]
Definition: rs_sensor.h:99
Definition: RsSink.h:16
static RsMediaSession * createNew(UsageEnvironment &env, char const *sdpDescription)
static long long int getStreamProfileUniqueKey(rs2_video_stream t_profile)
unsigned sendSetParameterCommand(responseHandler *responseHandler, char const *parameterName, char const *parameterValue, Authenticator *authenticator=NULL)
GLfloat value
std::string msg
Definition: RsRtspCommon.h:18
#define RTSP_CLIENT_COMMANDS_TIMEOUT_SEC
Definition: RsRtspClient.h:22
All the parameters required to define a video stream.
Definition: rs_internal.h:41
#define REQUEST_STREAMING_OVER_TCP
std::string format_error_msg(std::string function, RsRtspReturnValue retVal)
virtual int start()
Definition: RsRtspCommon.h:8
std::condition_variable m_cv
Definition: RsRtspClient.h:89
rs2_stream type
Definition: rs_internal.h:43
UsageEnvironment * m_env
Definition: RsRtspClient.h:96
static void subsessionByeHandler(void *clientData, char const *reason)
float coeffs[5]
Definition: rs_types.h:67
char & getEventLoopWatchVariable()
Definition: RsRtspClient.h:63
GLsizei const GLchar *const * string
static void continueAfterSETUP(RTSPClient *rtspClient, int resultCode, char *resultString)
RsRtspReturnValue m_lastReturnValue
Definition: RsRtspClient.h:86
RsRTSPClient(TaskScheduler *t_scheduler, UsageEnvironment *t_env, char const *t_rtspURL, int t_verbosityLevel, char const *t_applicationName, portNumBits t_tunnelOverHTTPPortNum, int idx)
StreamClientState m_scs
Definition: RsRtspClient.h:82
float rotation[9]
Definition: rs_sensor.h:98
GLuint index
void setDeviceData(DeviceData t_data)
GLenum GLuint GLenum GLsizei const GLchar * buf
RsRtspReturnCode
Definition: RsRtspCommon.h:6
GLuint64 key
Definition: glext.h:8966
RsMediaSubsession * next()
void setGetParamResponse(float t_res)
virtual int setOption(const std::string &t_sensorName, rs2_option t_option, float t_value)
Boolean setRequestFields(RequestRecord *request, char *&cmdURL, Boolean &cmdURLWasAllocated, char const *&protocolStr, char *&extraHeaders, Boolean &extraHeadersWereAllocated)
static void continueAfterTEARDOWN(RTSPClient *rtspClient, int resultCode, char *resultString)
RsMediaSession * m_session
GLdouble f
std::string name
Definition: IRsRtsp.h:17
#define SDP_EXTRINSICS_ARGS
Definition: RsRtspClient.h:24
Definition: getopt.h:41
GLsizeiptr size
unsigned sendGetParameterCommand(responseHandler *responseHandler, char const *parameterName, Authenticator *authenticator=NULL)
bool m_commandDone
Definition: RsRtspClient.h:91
float m_getParamRes
Definition: RsRtspClient.h:94
char m_eventLoopWatchVariable
Definition: RsRtspClient.h:97
virtual int getOption(const std::string &t_sensorName, rs2_option t_option, float &t_value)
GLuint counter
Definition: glext.h:5684
std::map< std::pair< int, int >, rs2_extrinsics > minimal_extrinsics_map
rs2::option_range range
Definition: RsCommon.h:40
GLint GLsizei GLsizei height
bool isActiveSession
Definition: RsRtspClient.h:83
GLint GLint GLsizei GLint GLenum format
DeviceData m_deviceData
Definition: RsRtspClient.h:92
static void continueAfterOPTIONS(RTSPClient *rtspClient, int resultCode, char *resultString)
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
static void continueAfterGETCOMMAND(RTSPClient *rtspClient, int resultCode, char *resultString)
std::vector< IpDeviceControlData > controls
#define DBG
Definition: NetdevLog.h:8
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
virtual int addStream(rs2_video_stream t_stream, rtp_callback *t_frameCallBack)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
static void continueAfterDESCRIBE(RTSPClient *rtspClient, int resultCode, char *resultString)
static void continueAfterPLAY(RTSPClient *rtspClient, int resultCode, char *resultString)
std::mutex & getTaskSchedulerMutex()
Definition: RsRtspClient.h:67
virtual ~RsRTSPClient()
rs2_distortion model
Definition: rs_types.h:66
static IRsRtsp * createNew(char const *t_rtspURL, char const *t_applicationName, portNumBits t_tunnelOverHTTPPortNum, int idx)
static RsSink * createNew(UsageEnvironment &t_env, MediaSubsession &t_subsession, rs2_video_stream t_stream, MemoryPool *t_mempool, char const *t_streamId=NULL)
Definition: RsSink.cpp:14
static void continueAfterSETCOMMAND(RTSPClient *rtspClient, int resultCode, char *resultString)
static bool & getIsEnabled()
float rs2_vector::* pos
static void continueAfterPAUSE(RTSPClient *rtspClient, int resultCode, char *resultString)
int stoi(const std::string &value)
#define NULL
Definition: tinycthread.c:47
MemoryPool * m_memPool
Definition: RsRtspClient.h:93
int i
GLuint res
Definition: glext.h:8856
rs2_intrinsics intrinsics
Definition: rs_internal.h:51
virtual std::vector< rs2_video_stream > getStreams()
#define RTSP_CLIENT_VERBOSITY_LEVEL
std::mutex m_commandMtx
Definition: RsRtspClient.h:90
static void subsessionAfterPlaying(void *clientData)
static RSUsageEnvironment * createNew(TaskScheduler &taskScheduler)
void schedulerThread(RsRTSPClient *t_rtspClientInstance)
GLuint64EXT * result
Definition: glext.h:10921
std::map< long long int, RsMediaSubsession * > m_subsessionMap
Definition: RsRtspClient.h:85
std::string usbType
Definition: IRsRtsp.h:18
GLint GLsizei width
void updateExtrinsicsMap(rs2_video_stream videoStream, std::string extrinsics_str)
void initFunc(MemoryPool *t_pool)
std::string to_string(T value)


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:41