Program Listing for File stream.h
↰ Return to documentation for file (rc_genicam_api/stream.h)
/*
* This file is part of the rc_genicam_api package.
*
* Copyright (c) 2017 Roboception GmbH
* All rights reserved
*
* Author: Heiko Hirschmueller
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder 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 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef RC_GENICAM_API_STREAM
#define RC_GENICAM_API_STREAM
#include "device.h"
#include "buffer.h"
#include <mutex>
namespace rcg
{
class Buffer;
class Stream : public std::enable_shared_from_this<Stream>
{
public:
Stream(const std::shared_ptr<Device> &parent,
const std::shared_ptr<const GenTLWrapper> &gentl, const char *id);
~Stream();
std::shared_ptr<Device> getParent() const;
const std::string &getID() const;
void open();
void close();
void attachBuffers(bool enable);
void startStreaming(int nacquire=-1);
void startStreaming(int nacquire, int min_buffers);
void stopStreaming();
int getAvailableBufferCount();
const Buffer *grab(int64_t timeout=-1);
uint64_t getNumDelivered();
uint64_t getNumUnderrun();
size_t getNumAnnounced();
size_t getNumQueued();
size_t getNumAwaitDelivery();
uint64_t getNumStarted();
size_t getPayloadSize();
bool getIsGrabbing();
bool getDefinesPayloadsize();
std::string getTLType();
size_t getNumChunksMax();
size_t getBufAnnounceMin();
size_t getBufAlignment();
std::shared_ptr<GenApi::CNodeMapRef> getNodeMap();
void *getHandle() const;
private:
Stream(class Stream &); // forbidden
Stream &operator=(const Stream &); // forbidden
Buffer buffer;
std::shared_ptr<Device> parent;
std::shared_ptr<const GenTLWrapper> gentl;
std::string id;
std::recursive_mutex mtx;
int n_open;
void *stream;
void *event;
size_t bn;
std::shared_ptr<CPort> cport;
std::shared_ptr<GenApi::CNodeMapRef> nodemap;
};
}
#endif