WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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 {
75 pixelFormat = 0;
76 width = 0;
77 height = 0;
78 fps = 0;
79 }
80 VideoMode(PixelFormat pixelFormat_, int width_, int height_, int fps_) {
81 pixelFormat = pixelFormat_;
82 width = width_;
83 height = height_;
84 fps = fps_;
85 }
86 explicit operator bool() const { return pixelFormat == kUnknown; }
87
88 bool operator==(const VideoMode& other) const {
89 return pixelFormat == other.pixelFormat && width == other.width &&
90 height == other.height && fps == other.fps;
91 }
92
93 bool CompareWithoutFps(const VideoMode& other) const {
94 return pixelFormat == other.pixelFormat && width == other.width &&
95 height == other.height;
96 }
97};
98
99/**
100 * Listener event
101 */
102struct RawEvent {
125
126 RawEvent() = default;
127 explicit RawEvent(RawEvent::Kind kind_) : kind{kind_} {}
128 RawEvent(std::string_view name_, CS_Handle handle_, RawEvent::Kind kind_)
129 : kind{kind_}, name{name_} {
130 if (kind_ == kSinkCreated || kind_ == kSinkDestroyed ||
131 kind_ == kSinkEnabled || kind_ == kSinkDisabled) {
132 sinkHandle = handle_;
133 } else {
134 sourceHandle = handle_;
135 }
136 }
137 RawEvent(std::string_view name_, CS_Source source_, const VideoMode& mode_)
139 sourceHandle{source_},
140 name{name_},
141 mode{mode_} {}
142 RawEvent(std::string_view name_, CS_Source source_, RawEvent::Kind kind_,
143 CS_Property property_, CS_PropertyKind propertyKind_, int value_,
144 std::string_view valueStr_)
145 : kind{kind_},
146 sourceHandle{source_},
147 name{name_},
148 propertyHandle{property_},
149 propertyKind{propertyKind_},
150 value{value_},
151 valueStr{valueStr_} {}
152
154
155 // Valid for kSource* and kSink* respectively
158
159 // Source/sink/property name
160 std::string name;
161
162 // Fields for kSourceVideoModeChanged event
164
165 // Fields for kSourceProperty* events
168 int value;
169 std::string valueStr;
170
171 // Listener that was triggered
173};
174
175/**
176 * @defgroup cscore_property_func Property Functions
177 * @{
178 */
180std::string GetPropertyName(CS_Property property, CS_Status* status);
181std::string_view GetPropertyName(CS_Property property,
183 CS_Status* status);
184int GetProperty(CS_Property property, CS_Status* status);
185void SetProperty(CS_Property property, int value, CS_Status* status);
186int GetPropertyMin(CS_Property property, CS_Status* status);
187int GetPropertyMax(CS_Property property, CS_Status* status);
188int GetPropertyStep(CS_Property property, CS_Status* status);
190std::string GetStringProperty(CS_Property property, CS_Status* status);
191std::string_view GetStringProperty(CS_Property property,
193 CS_Status* status);
194void SetStringProperty(CS_Property property, std::string_view value,
195 CS_Status* status);
196std::vector<std::string> GetEnumPropertyChoices(CS_Property property,
197 CS_Status* status);
198/** @} */
199
200/**
201 * @defgroup cscore_source_create_func Source Creation Functions
202 * @{
203 */
204CS_Source CreateUsbCameraDev(std::string_view name, int dev, CS_Status* status);
205CS_Source CreateUsbCameraPath(std::string_view name, std::string_view path,
206 CS_Status* status);
207CS_Source CreateHttpCamera(std::string_view name, std::string_view url,
208 CS_HttpCameraKind kind, CS_Status* status);
209CS_Source CreateHttpCamera(std::string_view name,
210 std::span<const std::string> urls,
211 CS_HttpCameraKind kind, CS_Status* status);
212CS_Source CreateCvSource(std::string_view name, const VideoMode& mode,
213 CS_Status* status);
214/** @} */
215
216/**
217 * @defgroup cscore_source_func Source Functions
218 * @{
219 */
224 CS_Status* status);
228 CS_Status* status);
231 CS_ConnectionStrategy strategy,
232 CS_Status* status);
236 CS_Status* status);
237std::span<CS_Property> EnumerateSourceProperties(
239 CS_Status* status);
242 CS_Status* status);
244 CS_Status* status);
245bool SetSourceResolution(CS_Source source, int width, int height,
246 CS_Status* status);
247bool SetSourceFPS(CS_Source source, int fps, CS_Status* status);
248bool SetSourceConfigJson(CS_Source source, std::string_view config,
249 CS_Status* status);
250bool SetSourceConfigJson(CS_Source source, const wpi::json& config,
251 CS_Status* status);
255 CS_Status* status);
258 CS_Status* status);
261/** @} */
262
263/**
264 * @defgroup cscore_camera_property_func Camera Source Common Property Functions
265 * @{
266 */
267void SetCameraBrightness(CS_Source source, int brightness, CS_Status* status);
272 CS_Status* status);
276/** @} */
277
278/**
279 * @defgroup cscore_usbcamera_func UsbCamera Source Functions
280 * @{
281 */
282void SetUsbCameraPath(CS_Source, std::string_view path, CS_Status* status);
285/** @} */
286
287/**
288 * @defgroup cscore_httpcamera_func HttpCamera Source Functions
289 * @{
290 */
292void SetHttpCameraUrls(CS_Source source, std::span<const std::string> urls,
293 CS_Status* status);
294std::vector<std::string> GetHttpCameraUrls(CS_Source source, CS_Status* status);
295/** @} */
296
297/**
298 * @defgroup cscore_frame_source_func Frame Source Functions
299 * @{
300 */
301void NotifySourceError(CS_Source source, std::string_view msg,
302 CS_Status* status);
303void SetSourceConnected(CS_Source source, bool connected, CS_Status* status);
304void SetSourceDescription(CS_Source source, std::string_view description,
305 CS_Status* status);
307 CS_PropertyKind kind, int minimum, int maximum,
308 int step, int defaultValue, int value,
309 CS_Status* status);
311 std::span<const std::string> choices,
312 CS_Status* status);
313/** @} */
314
315/**
316 * @defgroup cscore_sink_create_func Sink Creation Functions
317 * @{
318 */
319CS_Sink CreateMjpegServer(std::string_view name, std::string_view listenAddress,
320 int port, CS_Status* status);
321CS_Sink CreateCvSink(std::string_view name, VideoMode::PixelFormat pixelFormat,
322 CS_Status* status);
323CS_Sink CreateCvSinkCallback(std::string_view name,
324 VideoMode::PixelFormat pixelFormat,
325 std::function<void(uint64_t time)> processFrame,
326 CS_Status* status);
327
328/** @} */
329
330/**
331 * @defgroup cscore_sink_func Sink Functions
332 * @{
333 */
335std::string GetSinkName(CS_Sink sink, CS_Status* status);
337 CS_Status* status);
338std::string GetSinkDescription(CS_Sink sink, CS_Status* status);
339std::string_view GetSinkDescription(CS_Sink sink,
341 CS_Status* status);
342CS_Property GetSinkProperty(CS_Sink sink, std::string_view name,
343 CS_Status* status);
344std::span<CS_Property> EnumerateSinkProperties(
347CS_Property GetSinkSourceProperty(CS_Sink sink, std::string_view name,
348 CS_Status* status);
349bool SetSinkConfigJson(CS_Sink sink, std::string_view config,
350 CS_Status* status);
351bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config,
352 CS_Status* status);
353std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status);
357void ReleaseSink(CS_Sink sink, CS_Status* status);
358/** @} */
359
360/**
361 * @defgroup cscore_mjpegserver_func MjpegServer Sink Functions
362 * @{
363 */
366/** @} */
367
368/**
369 * @defgroup cscore_frame_sink_func Frame Sink Functions
370 * @{
371 */
372void SetSinkDescription(CS_Sink sink, std::string_view description,
373 CS_Status* status);
374std::string GetSinkError(CS_Sink sink, CS_Status* status);
376 CS_Status* status);
377void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status);
378/** @} */
379
380/**
381 * @defgroup cscore_listener_func Listener Functions
382 * @{
383 */
384void SetListenerOnStart(std::function<void()> onStart);
385void SetListenerOnExit(std::function<void()> onExit);
386
387CS_Listener AddListener(std::function<void(const RawEvent& event)> callback,
388 int eventMask, bool immediateNotify, CS_Status* status);
389
391
395 bool immediateNotify, CS_Status* status);
396std::vector<RawEvent> PollListener(CS_ListenerPoller poller);
397std::vector<RawEvent> PollListener(CS_ListenerPoller poller, double timeout,
398 bool* timedOut);
400/** @} */
401
403
404/**
405 * @defgroup cscore_telemetry_func Telemetry Functions
406 * @{
407 */
408void SetTelemetryPeriod(double seconds);
411 CS_Status* status);
413 CS_Status* status);
414/** @} */
415
416/**
417 * @defgroup cscore_logging_func Logging Functions
418 * @{
419 */
420using LogFunc = std::function<void(unsigned int level, const char* file,
421 unsigned int line, const char* msg)>;
422void SetLogger(LogFunc func, unsigned int min_level);
423void SetDefaultLogger(unsigned int min_level);
424/** @} */
425
426/**
427 * @defgroup cscore_shutdown_func Library Shutdown Function
428 * @{
429 */
430void Shutdown();
431/** @} */
432
433/**
434 * @defgroup cscore_utility_func Utility Functions
435 * @{
436 */
437std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status);
438
439std::span<CS_Source> EnumerateSourceHandles(
442 CS_Status* status);
443
444std::string GetHostname();
445
446std::vector<std::string> GetNetworkInterfaces();
447/** @} */
448
449/** @} */
450
451} // namespace cs
452
453#ifdef _WIN32
454// Disable uninitialized variable warnings
455#pragma warning(pop)
456#endif
457
458#endif // CSCORE_CSCORE_CPP_H_
@ WPI_PIXFMT_YUYV
Definition RawFrame.h:54
@ WPI_PIXFMT_Y16
Definition RawFrame.h:58
@ WPI_PIXFMT_UYVY
Definition RawFrame.h:59
@ WPI_PIXFMT_BGRA
Definition RawFrame.h:60
@ WPI_PIXFMT_MJPEG
Definition RawFrame.h:53
@ WPI_PIXFMT_GRAY
Definition RawFrame.h:57
@ WPI_PIXFMT_RGB565
Definition RawFrame.h:55
@ WPI_PIXFMT_BGR
Definition RawFrame.h:56
@ WPI_PIXFMT_UNKNOWN
Definition RawFrame.h:52
This file defines the SmallVector class.
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 and nanopb were all modified for use in 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:124
This class consists of common code factored out of the SmallVector class to reduce code duplication b...
Definition sha1.h:30
CS_ConnectionStrategy
Connection strategy.
Definition cscore_c.h:177
CS_HttpCameraKind
HTTP Camera kinds.
Definition cscore_c.h:125
CS_PropertyKind
Property kinds.
Definition cscore_c.h:103
CS_TelemetryKind
Telemetry kinds.
Definition cscore_c.h:171
CS_SinkKind
Sink kinds.
Definition cscore_c.h:135
CS_SourceKind
Source kinds.
Definition cscore_c.h:114
@ CS_SOURCE_PROPERTY_CREATED
Definition cscore_c.h:152
@ CS_SOURCE_VIDEOMODES_UPDATED
Definition cscore_c.h:150
@ CS_SINK_PROPERTY_VALUE_UPDATED
Definition cscore_c.h:163
@ CS_SOURCE_CONNECTED
Definition cscore_c.h:148
@ CS_TELEMETRY_UPDATED
Definition cscore_c.h:161
@ CS_SINK_ENABLED
Definition cscore_c.h:158
@ CS_USB_CAMERAS_CHANGED
Definition cscore_c.h:165
@ CS_SOURCE_CREATED
Definition cscore_c.h:146
@ CS_SINK_DESTROYED
Definition cscore_c.h:157
@ CS_SINK_PROPERTY_CREATED
Definition cscore_c.h:162
@ CS_SINK_PROPERTY_CHOICES_UPDATED
Definition cscore_c.h:164
@ CS_NETWORK_INTERFACES_CHANGED
Definition cscore_c.h:160
@ CS_SOURCE_VIDEOMODE_CHANGED
Definition cscore_c.h:151
@ CS_SINK_SOURCE_CHANGED
Definition cscore_c.h:155
@ CS_SOURCE_PROPERTY_VALUE_UPDATED
Definition cscore_c.h:153
@ CS_SOURCE_DISCONNECTED
Definition cscore_c.h:149
@ CS_SOURCE_DESTROYED
Definition cscore_c.h:147
@ CS_SINK_CREATED
Definition cscore_c.h:156
@ CS_SOURCE_PROPERTY_CHOICES_UPDATED
Definition cscore_c.h:154
@ CS_SINK_DISABLED
Definition cscore_c.h:159
@ CS_INVALID_HANDLE
Definition cscore_c.h:63
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()
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)
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)
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:54
int CS_Status
Definition cscore_c.h:47
CS_Handle CS_ListenerPoller
Definition cscore_c.h:52
CS_Handle CS_Property
Definition cscore_c.h:50
CS_Handle CS_Sink
Definition cscore_c.h:53
int CS_Handle
Definition cscore_c.h:49
CS_Handle CS_Listener
Definition cscore_c.h:51
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 ShuffleboardContainer.h:25
Video mode.
Definition cscore_c.h:93
int width
Definition cscore_c.h:95
int pixelFormat
Definition cscore_c.h:94
int fps
Definition cscore_c.h:97
int height
Definition cscore_c.h:96
Listener event.
Definition cscore_cpp.h:102
VideoMode mode
Definition cscore_cpp.h:163
CS_Sink sinkHandle
Definition cscore_cpp.h:157
int value
Definition cscore_cpp.h:168
std::string name
Definition cscore_cpp.h:160
Kind kind
Definition cscore_cpp.h:153
CS_Property propertyHandle
Definition cscore_cpp.h:166
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:142
CS_Source sourceHandle
Definition cscore_cpp.h:156
std::string valueStr
Definition cscore_cpp.h:169
RawEvent(RawEvent::Kind kind_)
Definition cscore_cpp.h:127
RawEvent(std::string_view name_, CS_Source source_, const VideoMode &mode_)
Definition cscore_cpp.h:137
CS_Listener listener
Definition cscore_cpp.h:172
RawEvent(std::string_view name_, CS_Handle handle_, RawEvent::Kind kind_)
Definition cscore_cpp.h:128
CS_PropertyKind propertyKind
Definition cscore_cpp.h:167
Kind
Definition cscore_cpp.h:103
@ kTelemetryUpdated
Definition cscore_cpp.h:119
@ kUsbCamerasChanged
Definition cscore_cpp.h:123
@ kSinkSourceChanged
Definition cscore_cpp.h:113
@ kSourcePropertyCreated
Definition cscore_cpp.h:110
@ kSinkEnabled
Definition cscore_cpp.h:116
@ kSinkPropertyCreated
Definition cscore_cpp.h:120
@ kSourceVideoModeChanged
Definition cscore_cpp.h:109
@ kSinkDisabled
Definition cscore_cpp.h:117
@ kSourcePropertyValueUpdated
Definition cscore_cpp.h:111
@ kSinkPropertyValueUpdated
Definition cscore_cpp.h:121
@ kSinkPropertyChoicesUpdated
Definition cscore_cpp.h:122
@ kSinkCreated
Definition cscore_cpp.h:114
@ kSourceCreated
Definition cscore_cpp.h:104
@ kSourceDisconnected
Definition cscore_cpp.h:107
@ kNetworkInterfacesChanged
Definition cscore_cpp.h:118
@ kSinkDestroyed
Definition cscore_cpp.h:115
@ kSourcePropertyChoicesUpdated
Definition cscore_cpp.h:112
@ kSourceDestroyed
Definition cscore_cpp.h:105
@ kSourceVideoModesUpdated
Definition cscore_cpp.h:108
@ kSourceConnected
Definition cscore_cpp.h:106
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:80
VideoMode()
Definition cscore_cpp.h:74
bool CompareWithoutFps(const VideoMode &other) const
Definition cscore_cpp.h:93
bool operator==(const VideoMode &other) const
Definition cscore_cpp.h:88
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
@ kBGRA
Definition cscore_cpp.h:72
@ kMJPEG
Definition cscore_cpp.h:65
@ kY16
Definition cscore_cpp.h:70
@ kUYVY
Definition cscore_cpp.h:71
@ kRGB565
Definition cscore_cpp.h:67