cameraUVC.h
1 /*
2  * Player - One Hell of a Robot Server
3  * Copyright (C) 2006
4  * Raymond Sheh, Luke Gumbley
5  *
6  *
7  * This program is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program; if not, write to the Free Software
19  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
20  *
21  */
22 
23 #include <libplayercore/playercore.h>
24 
25 #include "UvcInterface.h"
26 
27 class CameraUvc;
28 
29 #ifndef CAMERAUVC_H_
30 #define CAMERAUVC_H_
31 
32 class CameraUvc : public ThreadedDriver
33 {
34  public:
35  CameraUvc(ConfigFile* cf, int section);
36  ~CameraUvc();
37  int MainSetup();
38  void MainQuit();
39 
40  int ProcessMessage(QueuePointer &resp_queue, player_msghdr *hdr, void *data);
41  private:
42  virtual void Main();
43 
44  UvcInterface *ui;
45 
46  player_camera_data_t data; // Data to send to client (through the server)
47 };
48 
49 #endif /*CAMERAUVC_H_*/
Request to get an integer property.
Definition: player.h:459
#define PLAYER_WARN1(msg, a)
Error message macros.
Definition: error.h:90
String Property Class.
Definition: property.h:171
#define PLAYER_MSG1(level, msg, a)
Error message macros.
Definition: error.h:106
virtual void Publish(player_devaddr_t addr, QueuePointer &queue, uint8_t type, uint8_t subtype, void *src=NULL, size_t deprecated=0, double *timestamp=NULL, bool copy=true)
Publish a message via one of this driver's interfaces.
int MainSetup()
Sets up the resources needed by the driver thread.
Definition: cameraUVC.cc:130
static bool MatchMessage(player_msghdr_t *hdr, int type, int subtype, player_devaddr_t addr)
Helper for message processing.
Definition: message.h:159
double ReadFloat(int section, const char *name, double value)
Read a floating point (double) value.
Definition: cameraUVC.h:33
#define PLAYER_SET_STRPROP_REQ
String property set request subtype.
Definition: player.h:440
Generic message header.
Definition: player.h:162
unsigned int GetDataSize()
Size of message data.
Definition: message.h:190
virtual int MainSetup(void)
Sets up the resources needed by the driver thread.
Definition: driver.h:658
virtual void MainQuit(void)
Cleanup method for driver thread (called when main exits)
Definition: driver.h:664
uint8_t type
Message type; must be one of PLAYER_MSGTYPE_*.
Definition: player.h:166
#define PLAYER_WARN3(msg, a, b, c)
Error message macros.
Definition: error.h:92
Encapsulates a device (i.e., a driver bound to an interface)
Definition: device.h:75
const char * ReadString(int section, const char *name, const char *value)
Read a string value.
uint8_t subtype
Message subtype; interface specific.
Definition: player.h:168
virtual void Main(void)=0
Main method for driver thread.
int ReadInt(int section, const char *name, int value)
Read an integer value.
void * GetPayload()
Get pointer to payload.
Definition: message.h:188
void ProcessMessages(void)
Process pending messages.
#define PLAYER_MSGTYPE_DATA
A data message.
Definition: player.h:95
#define PLAYER_ERROR2(msg, a, b)
Error message macros.
Definition: error.h:83
int32_t value
The property value.
Definition: player.h:465
#define PLAYER_MSGTYPE_RESP_ACK
A positive response message.
Definition: player.h:112
virtual int ProcessMessage(QueuePointer &resp_queue, player_msghdr *hdr, void *data)
Message handler.
static bool MatchDeviceAddress(player_devaddr_t addr1, player_devaddr_t addr2)
Compare two addresses.
Definition: device.h:201
bool ReadBool(int section, const char *name, bool value)
Read a boolean value (one of: yes, no, true, false, 1, 0)
#define PLAYER_MSGTYPE_REQ
A request message.
Definition: player.h:106
int ProcessMessage(QueuePointer &resp_queue, player_msghdr *hdr, void *data)
Message handler.
Definition: cameraUVC.cc:194
#define PLAYER_MSGTYPE_RESP_NACK
A negative response message.
Definition: player.h:125
Integer property class.
Definition: property.h:115
int ReadDeviceAddr(player_devaddr_t *addr, int section, const char *name, int code, int index, const char *key)
Read a device id.
Class for loading configuration file information.
Definition: configfile.h:197
int ReadTupleInt(int section, const char *name, int index, int value)
Read an integer from a tuple field.
A device address.
Definition: player.h:146
An autopointer for the message queue.
Definition: message.h:74
char * key
The property key.
Definition: player.h:485
void MainQuit()
Cleanup method for driver thread (called when main exits)
Definition: cameraUVC.cc:150
Definition: UvcInterface.h:33
void SetError(int code)
Set/reset error code.
Definition: driver.h:145
#define PLAYER_ERROR1(msg, a)
Error message macros.
Definition: error.h:82
#define PLAYER_ERROR(msg)
Error message macros.
Definition: error.h:81
player_devaddr_t device_addr
Default device address (single-interface drivers)
Definition: driver.h:269
Base class for drivers which oeprate with a thread.
Definition: driver.h:553
double timestamp
Time associated with message contents (seconds since epoch)
Definition: player.h:170
uint32_t size
Size in bytes of the payload to follow.
Definition: player.h:174
char * key
The property key.
Definition: player.h:463
Reference-counted message objects.
Definition: message.h:133
#define PLAYER_WARN(msg)
Warning message macros.
Definition: error.h:89
Base class for all drivers.
Definition: driver.h:109
char * value
The property value.
Definition: player.h:489
Request to get a string property.
Definition: player.h:481
virtual void Main()
Main method for driver thread.
Definition: cameraUVC.cc:161
#define PLAYER_MSG2(level, msg, a, b)
Error message macros.
Definition: error.h:107
#define PLAYER_SET_INTPROP_REQ
Integer property set request subtype.
Definition: player.h:432
player_msghdr_t * GetHeader()
Get pointer to header.
Definition: message.h:186
player_devaddr_t addr
Device to which this message pertains.
Definition: player.h:164
#define PLAYER_MSGQUEUE_DEFAULT_MAXLEN
Default maximum length for a message queue.
Definition: player.h:76