WPILibC++ 2024.3.2
cscore_cpp.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#ifndef CSCORE_CSCORE_CPP_H_
6#define CSCORE_CSCORE_CPP_H_
7
8#include <stdint.h>
9
10#include <functional>
11#include <span>
12#include <string>
13#include <string_view>
14#include <vector>
15
16#include <wpi/RawFrame.h>
17#include <wpi/SmallVector.h>
18#include <wpi/json_fwd.h>
19
20#include "cscore_c.h"
21
22#ifdef _WIN32
23// Disable uninitialized variable warnings
24#pragma warning(push)
25#pragma warning(disable : 26495)
26#endif
27
28/** CameraServer (cscore) namespace */
29namespace cs {
30
31/**
32 * @defgroup cscore_cpp_api cscore C++ function API
33 *
34 * Handle-based interface for C++. Users are encouraged to use the
35 * object oriented interface instead; this interface is intended for use
36 * in applications such as JNI which require handle-based access.
37 *
38 * @{
39 */
40
41/**
42 * USB camera information
43 */
45 /** Device number (e.g. N in '/dev/videoN' on Linux) */
46 int dev = -1;
47 /** Path to device if available (e.g. '/dev/video0' on Linux) */
48 std::string path;
49 /** Vendor/model name of the camera as provided by the USB driver */
50 std::string name;
51 /** Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux) */
52 std::vector<std::string> otherPaths;
53 /** USB Vendor Id */
54 int vendorId = -1;
55 /** USB Product Id */
56 int productId = -1;
57};
58
59/**
60 * Video mode
61 */
62struct VideoMode : public CS_VideoMode {
72 };
74 pixelFormat = 0;
75 width = 0;
76 height = 0;
77 fps = 0;
78 }
79 VideoMode(PixelFormat pixelFormat_, int width_, int height_, int fps_) {
80 pixelFormat = pixelFormat_;
81 width = width_;
82 height = height_;
83 fps = fps_;
84 }
85 explicit operator bool() const { return pixelFormat == kUnknown; }
86
87 bool operator==(const VideoMode& other) const {
88 return pixelFormat == other.pixelFormat && width == other.width &&
89 height == other.height && fps == other.fps;
90 }
91
92 bool CompareWithoutFps(const VideoMode& other) const {
93 return pixelFormat == other.pixelFormat && width == other.width &&
94 height == other.height;
95 }
96};
97
98/**
99 * Listener event
100 */
101struct RawEvent {
102 enum Kind {
123 };
124
125 RawEvent() = default;
126 explicit RawEvent(RawEvent::Kind kind_) : kind{kind_} {}
128 : kind{kind_}, name{name_} {
129 if (kind_ == kSinkCreated || kind_ == kSinkDestroyed ||
130 kind_ == kSinkEnabled || kind_ == kSinkDisabled) {
131 sinkHandle = handle_;
132 } else {
133 sourceHandle = handle_;
134 }
135 }
136 RawEvent(std::string_view name_, CS_Source source_, const VideoMode& mode_)
138 sourceHandle{source_},
139 name{name_},
140 mode{mode_} {}
142 CS_Property property_, CS_PropertyKind propertyKind_, int value_,
143 std::string_view valueStr_)
144 : kind{kind_},
145 sourceHandle{source_},
146 name{name_},
147 propertyHandle{property_},
148 propertyKind{propertyKind_},
149 value{value_},
150 valueStr{valueStr_} {}
151
153
154 // Valid for kSource* and kSink* respectively
157
158 // Source/sink/property name
159 std::string name;
160
161 // Fields for kSourceVideoModeChanged event
163
164 // Fields for kSourceProperty* events
167 int value;
168 std::string valueStr;
169
170 // Listener that was triggered
172};
173
174/**
175 * @defgroup cscore_property_func Property Functions
176 * @{
177 */
179std::string GetPropertyName(CS_Property property, CS_Status* status);
182 CS_Status* status);
183int GetProperty(CS_Property property, CS_Status* status);
184void SetProperty(CS_Property property, int value, CS_Status* status);
185int GetPropertyMin(CS_Property property, CS_Status* status);
186int GetPropertyMax(CS_Property property, CS_Status* status);
187int GetPropertyStep(CS_Property property, CS_Status* status);
189std::string GetStringProperty(CS_Property property, CS_Status* status);
192 CS_Status* status);
194 CS_Status* status);
195std::vector<std::string> GetEnumPropertyChoices(CS_Property property,
196 CS_Status* status);
197/** @} */
198
199/**
200 * @defgroup cscore_source_create_func Source Creation Functions
201 * @{
202 */
205 CS_Status* status);
207 CS_HttpCameraKind kind, CS_Status* status);
209 std::span<const std::string> urls,
210 CS_HttpCameraKind kind, CS_Status* status);
212 CS_Status* status);
213/** @} */
214
215/**
216 * @defgroup cscore_source_func Source Functions
217 * @{
218 */
223 CS_Status* status);
227 CS_Status* status);
230 CS_ConnectionStrategy strategy,
231 CS_Status* status);
235 CS_Status* status);
236std::span<CS_Property> EnumerateSourceProperties(
238 CS_Status* status);
241 CS_Status* status);
243 CS_Status* status);
244bool SetSourceResolution(CS_Source source, int width, int height,
245 CS_Status* status);
248 CS_Status* status);
249bool SetSourceConfigJson(CS_Source source, const wpi::json& config,
250 CS_Status* status);
254 CS_Status* status);
257 CS_Status* status);
260/** @} */
261
262/**
263 * @defgroup cscore_camera_property_func Camera Source Common Property Functions
264 * @{
265 */
266void SetCameraBrightness(CS_Source source, int brightness, CS_Status* status);
271 CS_Status* status);
275/** @} */
276
277/**
278 * @defgroup cscore_usbcamera_func UsbCamera Source Functions
279 * @{
280 */
284/** @} */
285
286/**
287 * @defgroup cscore_httpcamera_func HttpCamera Source Functions
288 * @{
289 */
291void SetHttpCameraUrls(CS_Source source, std::span<const std::string> urls,
292 CS_Status* status);
293std::vector<std::string> GetHttpCameraUrls(CS_Source source, CS_Status* status);
294/** @} */
295
296/**
297 * @defgroup cscore_opencv_source_func OpenCV Source Functions
298 * @{
299 */
301 CS_Status* status);
302void SetSourceConnected(CS_Source source, bool connected, CS_Status* status);
304 CS_Status* status);
306 CS_PropertyKind kind, int minimum, int maximum,
307 int step, int defaultValue, int value,
308 CS_Status* status);
310 std::span<const std::string> choices,
311 CS_Status* status);
312/** @} */
313
314/**
315 * @defgroup cscore_sink_create_func Sink Creation Functions
316 * @{
317 */
319 int port, CS_Status* status);
321 CS_Status* status);
323 VideoMode::PixelFormat pixelFormat,
324 std::function<void(uint64_t time)> processFrame,
325 CS_Status* status);
326
327/** @} */
328
329/**
330 * @defgroup cscore_sink_func Sink Functions
331 * @{
332 */
334std::string GetSinkName(CS_Sink sink, CS_Status* status);
336 CS_Status* status);
337std::string GetSinkDescription(CS_Sink sink, CS_Status* status);
340 CS_Status* status);
342 CS_Status* status);
343std::span<CS_Property> EnumerateSinkProperties(
347 CS_Status* status);
349 CS_Status* status);
350bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config,
351 CS_Status* status);
352std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status);
356void ReleaseSink(CS_Sink sink, CS_Status* status);
357/** @} */
358
359/**
360 * @defgroup cscore_mjpegserver_func MjpegServer Sink Functions
361 * @{
362 */
365/** @} */
366
367/**
368 * @defgroup cscore_opencv_sink_func OpenCV Sink Functions
369 * @{
370 */
372 CS_Status* status);
373std::string GetSinkError(CS_Sink sink, CS_Status* status);
375 CS_Status* status);
376void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status);
377/** @} */
378
379/**
380 * @defgroup cscore_listener_func Listener Functions
381 * @{
382 */
383void SetListenerOnStart(std::function<void()> onStart);
384void SetListenerOnExit(std::function<void()> onExit);
385
386CS_Listener AddListener(std::function<void(const RawEvent& event)> callback,
387 int eventMask, bool immediateNotify, CS_Status* status);
388
390
394 bool immediateNotify, CS_Status* status);
395std::vector<RawEvent> PollListener(CS_ListenerPoller poller);
396std::vector<RawEvent> PollListener(CS_ListenerPoller poller, double timeout,
397 bool* timedOut);
399/** @} */
400
402
403/**
404 * @defgroup cscore_telemetry_func Telemetry Functions
405 * @{
406 */
407void SetTelemetryPeriod(double seconds);
410 CS_Status* status);
412 CS_Status* status);
413/** @} */
414
415/**
416 * @defgroup cscore_logging_func Logging Functions
417 * @{
418 */
419using LogFunc = std::function<void(unsigned int level, const char* file,
420 unsigned int line, const char* msg)>;
421void SetLogger(LogFunc func, unsigned int min_level);
422void SetDefaultLogger(unsigned int min_level);
423/** @} */
424
425/**
426 * @defgroup cscore_shutdown_func Library Shutdown Function
427 * @{
428 */
429void Shutdown();
430/** @} */
431
432/**
433 * @defgroup cscore_utility_func Utility Functions
434 * @{
435 */
436std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status);
437
438std::span<CS_Source> EnumerateSourceHandles(
441 CS_Status* status);
442
443std::string GetHostname();
444
445std::vector<std::string> GetNetworkInterfaces();
446/** @} */
447
448/** @} */
449
450} // namespace cs
451
452#ifdef _WIN32
453// Disable uninitialized variable warnings
454#pragma warning(pop)
455#endif
456
457#endif // CSCORE_CSCORE_CPP_H_
@ WPI_PIXFMT_YUYV
Definition: RawFrame.h:52
@ WPI_PIXFMT_Y16
Definition: RawFrame.h:56
@ WPI_PIXFMT_UYVY
Definition: RawFrame.h:57
@ WPI_PIXFMT_MJPEG
Definition: RawFrame.h:51
@ WPI_PIXFMT_GRAY
Definition: RawFrame.h:55
@ WPI_PIXFMT_RGB565
Definition: RawFrame.h:53
@ WPI_PIXFMT_BGR
Definition: RawFrame.h:54
@ WPI_PIXFMT_UNKNOWN
Definition: RawFrame.h:50
This file defines the SmallVector class.
then any Derivative Works that You distribute must include a readable copy of the attribution notices contained within such NOTICE file
Definition: ThirdPartyNotices.txt:192
and restrictions which apply to each piece of software is included later in this file and or inside of the individual applicable source files The disclaimer of warranty in the WPILib license above applies to all code in and nothing in any of the other licenses gives permission to use the names of FIRST nor the names of the WPILib contributors to endorse or promote products derived from this software The following pieces of software have additional or alternate and or Google Inc All rights reserved Redistribution and use in source and binary with or without are permitted provided that the following conditions are this list of conditions and the following disclaimer *Redistributions in binary form must reproduce the above copyright this list of conditions and the following disclaimer in the documentation and or other materials provided with the distribution *Neither the name of Google Inc nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS AND ANY EXPRESS OR IMPLIED BUT NOT LIMITED THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY OR CONSEQUENTIAL WHETHER IN STRICT OR EVEN IF ADVISED OF THE POSSIBILITY OF SUCH January AND DISTRIBUTION Definitions License shall mean the terms and conditions for and distribution as defined by Sections through of this document Licensor shall mean the copyright owner or entity authorized by the copyright owner that is granting the License Legal Entity shall mean the union of the acting entity and all other entities that control are controlled by or are under common control with that entity For the purposes of this definition control direct or to cause the direction or management of such whether by contract or including but not limited to software source documentation source
Definition: ThirdPartyNotices.txt:111
basic_string_view< char > string_view
Definition: core.h:501
CS_ConnectionStrategy
Connection strategy.
Definition: cscore_c.h:176
CS_HttpCameraKind
HTTP Camera kinds.
Definition: cscore_c.h:124
CS_PropertyKind
Property kinds.
Definition: cscore_c.h:102
CS_TelemetryKind
Telemetry kinds.
Definition: cscore_c.h:170
CS_SinkKind
Sink kinds.
Definition: cscore_c.h:134
CS_SourceKind
Source kinds.
Definition: cscore_c.h:113
@ CS_SOURCE_PROPERTY_CREATED
Definition: cscore_c.h:151
@ CS_SOURCE_VIDEOMODES_UPDATED
Definition: cscore_c.h:149
@ CS_SINK_PROPERTY_VALUE_UPDATED
Definition: cscore_c.h:162
@ CS_SOURCE_CONNECTED
Definition: cscore_c.h:147
@ CS_TELEMETRY_UPDATED
Definition: cscore_c.h:160
@ CS_SINK_ENABLED
Definition: cscore_c.h:157
@ CS_USB_CAMERAS_CHANGED
Definition: cscore_c.h:164
@ CS_SOURCE_CREATED
Definition: cscore_c.h:145
@ CS_SINK_DESTROYED
Definition: cscore_c.h:156
@ CS_SINK_PROPERTY_CREATED
Definition: cscore_c.h:161
@ CS_SINK_PROPERTY_CHOICES_UPDATED
Definition: cscore_c.h:163
@ CS_NETWORK_INTERFACES_CHANGED
Definition: cscore_c.h:159
@ CS_SOURCE_VIDEOMODE_CHANGED
Definition: cscore_c.h:150
@ CS_SINK_SOURCE_CHANGED
Definition: cscore_c.h:154
@ CS_SOURCE_PROPERTY_VALUE_UPDATED
Definition: cscore_c.h:152
@ CS_SOURCE_DISCONNECTED
Definition: cscore_c.h:148
@ CS_SOURCE_DESTROYED
Definition: cscore_c.h:146
@ CS_SINK_CREATED
Definition: cscore_c.h:155
@ CS_SOURCE_PROPERTY_CHOICES_UPDATED
Definition: cscore_c.h:153
@ CS_SINK_DISABLED
Definition: cscore_c.h:158
@ CS_INVALID_HANDLE
Definition: cscore_c.h:62
int GetCameraBrightness(CS_Source source, CS_Status *status)
void SetCameraExposureManual(CS_Source source, int value, CS_Status *status)
void SetCameraExposureAuto(CS_Source source, CS_Status *status)
void SetCameraWhiteBalanceManual(CS_Source source, int value, CS_Status *status)
void SetCameraBrightness(CS_Source source, int brightness, CS_Status *status)
void SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status *status)
void SetCameraWhiteBalanceAuto(CS_Source source, CS_Status *status)
void SetCameraExposureHoldCurrent(CS_Source source, CS_Status *status)
bool NotifierDestroyed()
std::vector< std::string > GetHttpCameraUrls(CS_Source source, CS_Status *status)
void SetHttpCameraUrls(CS_Source source, std::span< const std::string > urls, CS_Status *status)
CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status *status)
CS_ListenerPoller CreateListenerPoller()
CS_Listener AddListener(std::function< void(const RawEvent &event)> callback, int eventMask, bool immediateNotify, CS_Status *status)
std::vector< RawEvent > PollListener(CS_ListenerPoller poller)
void CancelPollListener(CS_ListenerPoller poller)
CS_Listener AddPolledListener(CS_ListenerPoller poller, int eventMask, bool immediateNotify, CS_Status *status)
void SetListenerOnExit(std::function< void()> onExit)
void SetListenerOnStart(std::function< void()> onStart)
void RemoveListener(CS_Listener handle, CS_Status *status)
void DestroyListenerPoller(CS_ListenerPoller poller)
void SetDefaultLogger(unsigned int min_level)
std::function< void(unsigned int level, const char *file, unsigned int line, const char *msg)> LogFunc
Definition: cscore_cpp.h:420
void SetLogger(LogFunc func, unsigned int min_level)
int GetMjpegServerPort(CS_Sink sink, CS_Status *status)
std::string GetMjpegServerListenAddress(CS_Sink sink, CS_Status *status)
void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status *status)
void SetSinkDescription(CS_Sink sink, std::string_view description, CS_Status *status)
std::string GetSinkError(CS_Sink sink, CS_Status *status)
void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property, std::span< const std::string > choices, CS_Status *status)
void SetSourceConnected(CS_Source source, bool connected, CS_Status *status)
void SetSourceDescription(CS_Source source, std::string_view description, CS_Status *status)
CS_Property CreateSourceProperty(CS_Source source, std::string_view name, CS_PropertyKind kind, int minimum, int maximum, int step, int defaultValue, int value, CS_Status *status)
void NotifySourceError(CS_Source source, std::string_view msg, CS_Status *status)
int GetPropertyMin(CS_Property property, CS_Status *status)
void SetProperty(CS_Property property, int value, CS_Status *status)
void SetStringProperty(CS_Property property, std::string_view value, CS_Status *status)
CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status *status)
int GetPropertyDefault(CS_Property property, CS_Status *status)
int GetPropertyMax(CS_Property property, CS_Status *status)
int GetProperty(CS_Property property, CS_Status *status)
int GetPropertyStep(CS_Property property, CS_Status *status)
std::string GetStringProperty(CS_Property property, CS_Status *status)
std::vector< std::string > GetEnumPropertyChoices(CS_Property property, CS_Status *status)
std::string GetPropertyName(CS_Property property, CS_Status *status)
void Shutdown()
CS_Sink CreateCvSinkCallback(std::string_view name, VideoMode::PixelFormat pixelFormat, std::function< void(uint64_t time)> processFrame, CS_Status *status)
CS_Sink CreateCvSink(std::string_view name, VideoMode::PixelFormat pixelFormat, CS_Status *status)
CS_Sink CreateMjpegServer(std::string_view name, std::string_view listenAddress, int port, CS_Status *status)
bool SetSinkConfigJson(CS_Sink sink, std::string_view config, CS_Status *status)
CS_Source GetSinkSource(CS_Sink sink, CS_Status *status)
CS_Sink CopySink(CS_Sink sink, CS_Status *status)
wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status *status)
void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status *status)
CS_Property GetSinkSourceProperty(CS_Sink sink, std::string_view name, CS_Status *status)
void ReleaseSink(CS_Sink sink, CS_Status *status)
std::span< CS_Property > EnumerateSinkProperties(CS_Sink sink, wpi::SmallVectorImpl< CS_Property > &vec, CS_Status *status)
std::string GetSinkDescription(CS_Sink sink, CS_Status *status)
std::string GetSinkName(CS_Sink sink, CS_Status *status)
std::string GetSinkConfigJson(CS_Sink sink, CS_Status *status)
CS_SinkKind GetSinkKind(CS_Sink sink, CS_Status *status)
CS_Property GetSinkProperty(CS_Sink sink, std::string_view name, CS_Status *status)
CS_Source CreateUsbCameraPath(std::string_view name, std::string_view path, CS_Status *status)
CS_Source CreateHttpCamera(std::string_view name, std::string_view url, CS_HttpCameraKind kind, CS_Status *status)
CS_Source CreateUsbCameraDev(std::string_view name, int dev, CS_Status *status)
CS_Source CreateCvSource(std::string_view name, const VideoMode &mode, CS_Status *status)
void ReleaseSource(CS_Source source, CS_Status *status)
bool IsSourceConnected(CS_Source source, CS_Status *status)
uint64_t GetSourceLastFrameTime(CS_Source source, CS_Status *status)
bool SetSourceResolution(CS_Source source, int width, int height, CS_Status *status)
CS_Property GetSourceProperty(CS_Source source, std::string_view name, CS_Status *status)
bool SetSourceConfigJson(CS_Source source, std::string_view config, CS_Status *status)
bool SetSourcePixelFormat(CS_Source source, VideoMode::PixelFormat pixelFormat, CS_Status *status)
std::string GetSourceConfigJson(CS_Source source, CS_Status *status)
wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status *status)
void SetSourceConnectionStrategy(CS_Source source, CS_ConnectionStrategy strategy, CS_Status *status)
VideoMode GetSourceVideoMode(CS_Source source, CS_Status *status)
CS_Source CopySource(CS_Source source, CS_Status *status)
bool IsSourceEnabled(CS_Source source, CS_Status *status)
std::span< CS_Property > EnumerateSourceProperties(CS_Source source, wpi::SmallVectorImpl< CS_Property > &vec, CS_Status *status)
std::vector< VideoMode > EnumerateSourceVideoModes(CS_Source source, CS_Status *status)
CS_SourceKind GetSourceKind(CS_Source source, CS_Status *status)
std::string GetSourceName(CS_Source source, CS_Status *status)
std::string GetSourceDescription(CS_Source source, CS_Status *status)
bool SetSourceVideoMode(CS_Source source, const VideoMode &mode, CS_Status *status)
bool SetSourceFPS(CS_Source source, int fps, CS_Status *status)
std::span< CS_Sink > EnumerateSourceSinks(CS_Source source, wpi::SmallVectorImpl< CS_Sink > &vec, CS_Status *status)
int64_t GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status *status)
double GetTelemetryElapsedTime()
double GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status *status)
void SetTelemetryPeriod(double seconds)
CS_Handle CS_Source
Definition: cscore_c.h:53
int CS_Status
Definition: cscore_c.h:46
CS_Handle CS_ListenerPoller
Definition: cscore_c.h:51
CS_Handle CS_Property
Definition: cscore_c.h:49
CS_Handle CS_Sink
Definition: cscore_c.h:52
int CS_Handle
Definition: cscore_c.h:48
CS_Handle CS_Listener
Definition: cscore_c.h:50
UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status *status)
std::string GetUsbCameraPath(CS_Source source, CS_Status *status)
void SetUsbCameraPath(CS_Source, std::string_view path, CS_Status *status)
std::string GetHostname()
std::vector< UsbCameraInfo > EnumerateUsbCameras(CS_Status *status)
std::span< CS_Sink > EnumerateSinkHandles(wpi::SmallVectorImpl< CS_Sink > &vec, CS_Status *status)
std::span< CS_Source > EnumerateSourceHandles(wpi::SmallVectorImpl< CS_Source > &vec, CS_Status *status)
std::vector< std::string > GetNetworkInterfaces()
CameraServer (cscore) namespace.
Definition: cscore_oo.inc:16
fps
Definition: velocity.h:46
Video mode.
Definition: cscore_c.h:92
int width
Definition: cscore_c.h:94
int pixelFormat
Definition: cscore_c.h:93
int fps
Definition: cscore_c.h:96
int height
Definition: cscore_c.h:95
Listener event.
Definition: cscore_cpp.h:101
VideoMode mode
Definition: cscore_cpp.h:162
CS_Sink sinkHandle
Definition: cscore_cpp.h:156
int value
Definition: cscore_cpp.h:167
std::string name
Definition: cscore_cpp.h:159
Kind kind
Definition: cscore_cpp.h:152
CS_Property propertyHandle
Definition: cscore_cpp.h:165
RawEvent(std::string_view name_, CS_Source source_, RawEvent::Kind kind_, CS_Property property_, CS_PropertyKind propertyKind_, int value_, std::string_view valueStr_)
Definition: cscore_cpp.h:141
CS_Source sourceHandle
Definition: cscore_cpp.h:155
std::string valueStr
Definition: cscore_cpp.h:168
RawEvent(RawEvent::Kind kind_)
Definition: cscore_cpp.h:126
RawEvent(std::string_view name_, CS_Source source_, const VideoMode &mode_)
Definition: cscore_cpp.h:136
CS_Listener listener
Definition: cscore_cpp.h:171
RawEvent(std::string_view name_, CS_Handle handle_, RawEvent::Kind kind_)
Definition: cscore_cpp.h:127
CS_PropertyKind propertyKind
Definition: cscore_cpp.h:166
Kind
Definition: cscore_cpp.h:102
@ kTelemetryUpdated
Definition: cscore_cpp.h:118
@ kUsbCamerasChanged
Definition: cscore_cpp.h:122
@ kSinkSourceChanged
Definition: cscore_cpp.h:112
@ kSourcePropertyCreated
Definition: cscore_cpp.h:109
@ kSinkEnabled
Definition: cscore_cpp.h:115
@ kSinkPropertyCreated
Definition: cscore_cpp.h:119
@ kSourceVideoModeChanged
Definition: cscore_cpp.h:108
@ kSinkDisabled
Definition: cscore_cpp.h:116
@ kSourcePropertyValueUpdated
Definition: cscore_cpp.h:110
@ kSinkPropertyValueUpdated
Definition: cscore_cpp.h:120
@ kSinkPropertyChoicesUpdated
Definition: cscore_cpp.h:121
@ kSinkCreated
Definition: cscore_cpp.h:113
@ kSourceCreated
Definition: cscore_cpp.h:103
@ kSourceDisconnected
Definition: cscore_cpp.h:106
@ kNetworkInterfacesChanged
Definition: cscore_cpp.h:117
@ kSinkDestroyed
Definition: cscore_cpp.h:114
@ kSourcePropertyChoicesUpdated
Definition: cscore_cpp.h:111
@ kSourceDestroyed
Definition: cscore_cpp.h:104
@ kSourceVideoModesUpdated
Definition: cscore_cpp.h:107
@ kSourceConnected
Definition: cscore_cpp.h:105
RawEvent()=default
USB camera information.
Definition: cscore_cpp.h:44
int dev
Device number (e.g.
Definition: cscore_cpp.h:46
std::string name
Vendor/model name of the camera as provided by the USB driver.
Definition: cscore_cpp.h:50
int productId
USB Product Id.
Definition: cscore_cpp.h:56
int vendorId
USB Vendor Id.
Definition: cscore_cpp.h:54
std::string path
Path to device if available (e.g.
Definition: cscore_cpp.h:48
std::vector< std::string > otherPaths
Other path aliases to device (e.g.
Definition: cscore_cpp.h:52
Video mode.
Definition: cscore_cpp.h:62
VideoMode(PixelFormat pixelFormat_, int width_, int height_, int fps_)
Definition: cscore_cpp.h:79
VideoMode()
Definition: cscore_cpp.h:73
bool CompareWithoutFps(const VideoMode &other) const
Definition: cscore_cpp.h:92
bool operator==(const VideoMode &other) const
Definition: cscore_cpp.h:87
PixelFormat
Definition: cscore_cpp.h:63
@ kYUYV
Definition: cscore_cpp.h:66
@ kUnknown
Definition: cscore_cpp.h:64
@ kGray
Definition: cscore_cpp.h:69
@ kBGR
Definition: cscore_cpp.h:68
@ kMJPEG
Definition: cscore_cpp.h:65
@ kY16
Definition: cscore_cpp.h:70
@ kUYVY
Definition: cscore_cpp.h:71
@ kRGB565
Definition: cscore_cpp.h:67