Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Friends | List of all members
YSerialPort Class Reference

#include <yocto_serialport.h>

Inheritance diagram for YSerialPort:
Inheritance graph
[legend]

Public Member Functions

virtual int _invokeValueCallback (string value)
 
string command (void)
 
string currentJob (void)
 
int errCount (void)
 
string get_command (void)
 
virtual int get_CTS (void)
 
string get_currentJob (void)
 
int get_errCount (void)
 
string get_lastMsg (void)
 
string get_protocol (void)
 
int get_rxCount (void)
 
int get_rxMsgCount (void)
 
string get_serialMode (void)
 
string get_startupJob (void)
 
int get_txCount (void)
 
int get_txMsgCount (void)
 
Y_VOLTAGELEVEL_enum get_voltageLevel (void)
 
string lastMsg (void)
 
virtual vector< int > modbusReadBits (int slaveNo, int pduAddr, int nBits)
 
virtual vector< int > modbusReadInputBits (int slaveNo, int pduAddr, int nBits)
 
virtual vector< int > modbusReadInputRegisters (int slaveNo, int pduAddr, int nWords)
 
virtual vector< int > modbusReadRegisters (int slaveNo, int pduAddr, int nWords)
 
virtual vector< int > modbusWriteAndReadRegisters (int slaveNo, int pduWriteAddr, vector< int > values, int pduReadAddr, int nReadWords)
 
virtual int modbusWriteBit (int slaveNo, int pduAddr, int value)
 
virtual int modbusWriteBits (int slaveNo, int pduAddr, vector< int > bits)
 
virtual int modbusWriteRegister (int slaveNo, int pduAddr, int value)
 
virtual int modbusWriteRegisters (int slaveNo, int pduAddr, vector< int > values)
 
YSerialPortnext (void)
 
YSerialPortnextSerialPort (void)
 
string protocol (void)
 
virtual string queryLine (string query, int maxWait)
 
virtual vector< int > queryMODBUS (int slaveNo, vector< int > pduBytes)
 
virtual int read_avail (void)
 
virtual int read_seek (int absPos)
 
virtual int read_tell (void)
 
virtual vector< int > readArray (int nChars)
 
virtual string readBin (int nChars)
 
virtual int readByte (void)
 
virtual string readHex (int nBytes)
 
virtual string readLine (void)
 
virtual vector< string > readMessages (string pattern, int maxWait)
 
virtual string readStr (int nChars)
 
virtual int registerValueCallback (YSerialPortValueCallback callback)
 
virtual int reset (void)
 
int rxCount (void)
 
int rxMsgCount (void)
 
virtual int selectJob (string jobfile)
 
virtual int sendCommand (string text)
 
string serialMode (void)
 
int set_command (const string &newval)
 
int set_currentJob (const string &newval)
 
int set_protocol (const string &newval)
 
virtual int set_RTS (int val)
 
int set_serialMode (const string &newval)
 
int set_startupJob (const string &newval)
 
int set_voltageLevel (Y_VOLTAGELEVEL_enum newval)
 
int setCommand (const string &newval)
 
int setCurrentJob (const string &newval)
 
int setProtocol (const string &newval)
 
int setSerialMode (const string &newval)
 
int setStartupJob (const string &newval)
 
int setVoltageLevel (Y_VOLTAGELEVEL_enum newval)
 
virtual vector< YSnoopingRecordsnoopMessages (int maxWait)
 
string startupJob (void)
 
int txCount (void)
 
int txMsgCount (void)
 
virtual int uploadJob (string jobfile, string jsonDef)
 
Y_VOLTAGELEVEL_enum voltageLevel (void)
 
virtual int writeArray (vector< int > byteList)
 
virtual int writeBin (string buff)
 
virtual int writeByte (int code)
 
virtual int writeHex (string hexString)
 
virtual int writeLine (string text)
 
virtual int writeMODBUS (string hexString)
 
virtual int writeStr (string text)
 
 ~YSerialPort ()
 
- Public Member Functions inherited from YFunction
void _clearDataStreamCache ()
 
string _decode_json_string (const string &json)
 
string _download (const string &url)
 
YDataStream_findDataStream (YDataSet &dataset, const string &def)
 
string _get_json_path (const string &json, const string &path)
 
vector< string > _json_get_array (const string &json)
 
string _json_get_key (const string &json, const string &data)
 
string _json_get_string (const string &json)
 
int _parseEx (yJsonStateMachine &j)
 
virtual int _parserHelper (void)
 
string _parseString (yJsonStateMachine &j)
 
string _request (const string &request)
 
string _requestEx (int tcpchan, const string &request, yapiRequestProgressCallback callback, void *context)
 
void _throw (YRETCODE errType, string errMsg)
 
YRETCODE _upload (const string &path, const string &content)
 
YRETCODE _uploadWithProgress (const string &path, const string &content, yapiRequestProgressCallback callback, void *context)
 
string advertisedValue (void)
 
void clearCache ()
 
string describe (void)
 
string errMessage (void)
 
string errorMessage (void)
 
YRETCODE errorType (void)
 
YRETCODE errType (void)
 
YFUN_DESCR functionDescriptor (void)
 
string get_advertisedValue (void)
 
string get_errorMessage (void)
 
YRETCODE get_errorType (void)
 
virtual string get_friendlyName (void)
 
YFUN_DESCR get_functionDescriptor (void)
 
string get_functionId (void)
 
string get_hardwareId (void)
 
string get_hubSerial ()
 
string get_logicalName (void)
 
YModuleget_module (void)
 
void * get_userData (void)
 
bool isOnline (void)
 
YRETCODE load (int msValidity)
 
virtual string loadAttribute (string attrName)
 
string logicalName (void)
 
YModulemodule (void)
 
virtual int muteValueCallbacks (void)
 
YFunctionnext (void)
 
YFunctionnextFunction (void)
 
virtual int registerValueCallback (YFunctionValueCallback callback)
 
int set_advertisedValue (const string &newval)
 
int set_logicalName (const string &newval)
 
void set_userData (void *data)
 
int setAdvertisedValue (const string &newval)
 
int setLogicalName (const string &newval)
 
void setUserData (void *data)
 
virtual int unmuteValueCallbacks (void)
 
void * userData (void)
 
virtual ~YFunction ()
 

Static Public Member Functions

static YSerialPortFind (string func)
 
static YSerialPortFindSerialPort (string func)
 
static YSerialPortFirst (void)
 
static YSerialPortFirstSerialPort (void)
 
- Static Public Member Functions inherited from YFunction
static void _ClearCache (void)
 
static YFunctionFind (string func)
 
static YFunctionFindFunction (string func)
 
static YFunctionFirst (void)
 
static YFunctionFirstFunction (void)
 

Static Public Attributes

static const string COMMAND_INVALID = YAPI_INVALID_STRING
 
static const string CURRENTJOB_INVALID = YAPI_INVALID_STRING
 
static const int ERRCOUNT_INVALID = YAPI_INVALID_UINT
 
static const string LASTMSG_INVALID = YAPI_INVALID_STRING
 
static const string PROTOCOL_INVALID = YAPI_INVALID_STRING
 
static const int RXCOUNT_INVALID = YAPI_INVALID_UINT
 
static const int RXMSGCOUNT_INVALID = YAPI_INVALID_UINT
 
static const string SERIALMODE_INVALID = YAPI_INVALID_STRING
 
static const string STARTUPJOB_INVALID = YAPI_INVALID_STRING
 
static const int TXCOUNT_INVALID = YAPI_INVALID_UINT
 
static const int TXMSGCOUNT_INVALID = YAPI_INVALID_UINT
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_INVALID = Y_VOLTAGELEVEL_INVALID
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_OFF = Y_VOLTAGELEVEL_OFF
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_RS232 = Y_VOLTAGELEVEL_RS232
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_RS485 = Y_VOLTAGELEVEL_RS485
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_TTL3V = Y_VOLTAGELEVEL_TTL3V
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_TTL3VR = Y_VOLTAGELEVEL_TTL3VR
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_TTL5V = Y_VOLTAGELEVEL_TTL5V
 
static const Y_VOLTAGELEVEL_enum VOLTAGELEVEL_TTL5VR = Y_VOLTAGELEVEL_TTL5VR
 
- Static Public Attributes inherited from YFunction
static const string ADVERTISEDVALUE_INVALID = YAPI_INVALID_STRING
 
static const string FRIENDLYNAME_INVALID = YAPI_INVALID_STRING
 
static const YFUN_DESCR FUNCTIONDESCRIPTOR_INVALID = Y_FUNCTIONDESCRIPTOR_INVALID
 
static const string FUNCTIONID_INVALID = YAPI_INVALID_STRING
 
static const string HARDWAREID_INVALID = YAPI_INVALID_STRING
 
static const string LOGICALNAME_INVALID = YAPI_INVALID_STRING
 

Protected Member Functions

virtual int _parseAttr (YJSONObject *json_val)
 
 YSerialPort (const string &func)
 
- Protected Member Functions inherited from YFunction
YRETCODE _buildSetRequest (const string &changeattr, const string *changeval, string &request, string &errmsg)
 
string _escapeAttr (const string &changeval)
 
YRETCODE _getDescriptor (YFUN_DESCR &fundescr, string &errMsg)
 
YRETCODE _getDevice (YDevice *&dev, string &errMsg)
 
YRETCODE _load_unsafe (int msValidity)
 
YRETCODE _nextFunction (string &hwId)
 
int _parse (YJSONObject *j)
 
YRETCODE _setAttr (string attrname, string newvalue)
 
 YFunction (const string &func)
 

Protected Attributes

string _command
 
string _currentJob
 
int _errCount
 
string _lastMsg
 
string _protocol
 
string _rxbuff
 
int _rxbuffptr
 
int _rxCount
 
int _rxMsgCount
 
int _rxptr
 
string _serialMode
 
string _startupJob
 
int _txCount
 
int _txMsgCount
 
YSerialPortValueCallback _valueCallbackSerialPort
 
Y_VOLTAGELEVEL_enum _voltageLevel
 
- Protected Attributes inherited from YFunction
string _advertisedValue
 
u64 _cacheExpiration
 
string _className
 
std::map< string, YDataStream * > _dataStreams
 
string _func
 
YFUN_DESCR _fundescr
 
string _funId
 
string _hwId
 
string _lastErrorMsg
 
YRETCODE _lastErrorType
 
string _logicalName
 
string _serial
 
yCRITICAL_SECTION _this_cs
 
void * _userData
 
YFunctionValueCallback _valueCallbackFunction
 

Friends

YSerialPortyFindSerialPort (const string &func)
 
YSerialPortyFirstSerialPort (void)
 

Additional Inherited Members

- Static Protected Member Functions inherited from YFunction
static void _AddToCache (const string &classname, const string &func, YFunction *obj)
 
static YFunction_FindFromCache (const string &classname, const string &func)
 
static void _UpdateTimedReportCallbackList (YFunction *func, bool add)
 
static void _UpdateValueCallbackList (YFunction *func, bool add)
 
- Static Protected Attributes inherited from YFunction
static std::map< string, YFunction * > _cache
 

Detailed Description

YSerialPort Class: SerialPort function interface

The SerialPort function interface allows you to fully drive a Yoctopuce serial port, to send and receive data, and to configure communication parameters (baud rate, bit count, parity, flow control and protocol). Note that Yoctopuce serial ports are not exposed as virtual COM ports. They are meant to be used in the same way as all Yoctopuce devices.

Definition at line 139 of file yocto_serialport.h.

Constructor & Destructor Documentation

YSerialPort::YSerialPort ( const string &  func)
protected

Definition at line 110 of file yocto_serialport.cpp.

YSerialPort::~YSerialPort ( )

Definition at line 132 of file yocto_serialport.cpp.

Member Function Documentation

int YSerialPort::_invokeValueCallback ( string  value)
virtual

Reimplemented from YFunction.

Definition at line 790 of file yocto_serialport.cpp.

int YSerialPort::_parseAttr ( YJSONObject json_val)
protectedvirtual

Reimplemented from YFunction.

Definition at line 146 of file yocto_serialport.cpp.

string YSerialPort::command ( void  )
inline

Definition at line 326 of file yocto_serialport.h.

string YSerialPort::currentJob ( void  )
inline

Definition at line 279 of file yocto_serialport.h.

int YSerialPort::errCount ( void  )
inline

Definition at line 231 of file yocto_serialport.h.

static YSerialPort* YSerialPort::Find ( string  func)
inlinestatic

Definition at line 932 of file yocto_serialport.h.

YSerialPort * YSerialPort::FindSerialPort ( string  func)
static

Retrieves a serial port for a given identifier. The identifier can be specified using several formats:

  • FunctionLogicalName
  • ModuleSerialNumber.FunctionIdentifier
  • ModuleSerialNumber.FunctionLogicalName
  • ModuleLogicalName.FunctionIdentifier
  • ModuleLogicalName.FunctionLogicalName

This function does not require that the serial port is online at the time it is invoked. The returned object is nevertheless valid. Use the method YSerialPort.isOnline() to test if the serial port is indeed online at a given time. In case of ambiguity when looking for a serial port by logical name, no error is notified: the first instance found is returned. The search is performed first by hardware name, then by logical name.

If a call to this object's is_online() method returns FALSE although you are certain that the matching device is plugged, make sure that you did call registerHub() at application initialization time.

Parameters
func: a string that uniquely characterizes the serial port
Returns
a YSerialPort object allowing you to drive the serial port.

Definition at line 739 of file yocto_serialport.cpp.

static YSerialPort* YSerialPort::First ( void  )
inlinestatic

Definition at line 956 of file yocto_serialport.h.

YSerialPort * YSerialPort::FirstSerialPort ( void  )
static

Starts the enumeration of serial ports currently accessible. Use the method YSerialPort.nextSerialPort() to iterate on next serial ports.

Returns
a pointer to a YSerialPort object, corresponding to the first serial port currently online, or a NULL pointer if there are none.

Definition at line 2060 of file yocto_serialport.cpp.

string YSerialPort::get_command ( void  )

Definition at line 474 of file yocto_serialport.cpp.

int YSerialPort::get_CTS ( void  )
virtual

Reads the level of the CTS line. The CTS line is usually driven by the RTS signal of the connected serial device.

Returns
1 if the CTS line is high, 0 if the CTS line is low.

On failure, throws an exception or returns a negative error code.

Definition at line 1447 of file yocto_serialport.cpp.

string YSerialPort::get_currentJob ( void  )

Returns the name of the job file currently in use.

Returns
a string corresponding to the name of the job file currently in use

On failure, throws an exception or returns Y_CURRENTJOB_INVALID.

Definition at line 369 of file yocto_serialport.cpp.

int YSerialPort::get_errCount ( void  )

Returns the total number of communication errors detected since last reset.

Returns
an integer corresponding to the total number of communication errors detected since last reset

On failure, throws an exception or returns Y_ERRCOUNT_INVALID.

Definition at line 253 of file yocto_serialport.cpp.

string YSerialPort::get_lastMsg ( void  )

Returns the latest message fully received (for Line, Frame and Modbus protocols).

Returns
a string corresponding to the latest message fully received (for Line, Frame and Modbus protocols)

On failure, throws an exception or returns Y_LASTMSG_INVALID.

Definition at line 340 of file yocto_serialport.cpp.

string YSerialPort::get_protocol ( void  )

Returns the type of protocol used over the serial line, as a string. Possible values are "Line" for ASCII messages separated by CR and/or LF, "Frame:[timeout]ms" for binary messages separated by a delay time, "Modbus-ASCII" for MODBUS messages in ASCII mode, "Modbus-RTU" for MODBUS messages in RTU mode, "Wiegand-ASCII" for Wiegand messages in ASCII mode, "Wiegand-26","Wiegand-34", etc for Wiegand messages in byte mode, "Char" for a continuous ASCII stream or "Byte" for a continuous binary stream.

Returns
a string corresponding to the type of protocol used over the serial line, as a string

On failure, throws an exception or returns Y_PROTOCOL_INVALID.

Definition at line 589 of file yocto_serialport.cpp.

int YSerialPort::get_rxCount ( void  )

Returns the total number of bytes received since last reset.

Returns
an integer corresponding to the total number of bytes received since last reset

On failure, throws an exception or returns Y_RXCOUNT_INVALID.

Definition at line 195 of file yocto_serialport.cpp.

int YSerialPort::get_rxMsgCount ( void  )

Returns the total number of messages received since last reset.

Returns
an integer corresponding to the total number of messages received since last reset

On failure, throws an exception or returns Y_RXMSGCOUNT_INVALID.

Definition at line 282 of file yocto_serialport.cpp.

string YSerialPort::get_serialMode ( void  )

Returns the serial port communication parameters, as a string such as "9600,8N1". The string includes the baud rate, the number of data bits, the parity, and the number of stop bits. An optional suffix is included if flow control is active: "CtsRts" for hardware handshake, "XOnXOff" for logical flow control and "Simplex" for acquiring a shared bus using the RTS line (as used by some RS485 adapters for instance).

Returns
a string corresponding to the serial port communication parameters, as a string such as "9600,8N1"

On failure, throws an exception or returns Y_SERIALMODE_INVALID.

Definition at line 659 of file yocto_serialport.cpp.

string YSerialPort::get_startupJob ( void  )

Returns the job file to use when the device is powered on.

Returns
a string corresponding to the job file to use when the device is powered on

On failure, throws an exception or returns Y_STARTUPJOB_INVALID.

Definition at line 425 of file yocto_serialport.cpp.

int YSerialPort::get_txCount ( void  )

Returns the total number of bytes transmitted since last reset.

Returns
an integer corresponding to the total number of bytes transmitted since last reset

On failure, throws an exception or returns Y_TXCOUNT_INVALID.

Definition at line 224 of file yocto_serialport.cpp.

int YSerialPort::get_txMsgCount ( void  )

Returns the total number of messages send since last reset.

Returns
an integer corresponding to the total number of messages send since last reset

On failure, throws an exception or returns Y_TXMSGCOUNT_INVALID.

Definition at line 311 of file yocto_serialport.cpp.

Y_VOLTAGELEVEL_enum YSerialPort::get_voltageLevel ( void  )

Returns the voltage level used on the serial line.

Returns
a value among Y_VOLTAGELEVEL_OFF, Y_VOLTAGELEVEL_TTL3V, Y_VOLTAGELEVEL_TTL3VR, Y_VOLTAGELEVEL_TTL5V, Y_VOLTAGELEVEL_TTL5VR, Y_VOLTAGELEVEL_RS232 and Y_VOLTAGELEVEL_RS485 corresponding to the voltage level used on the serial line

On failure, throws an exception or returns Y_VOLTAGELEVEL_INVALID.

Definition at line 521 of file yocto_serialport.cpp.

string YSerialPort::lastMsg ( void  )
inline

Definition at line 267 of file yocto_serialport.h.

vector< int > YSerialPort::modbusReadBits ( int  slaveNo,
int  pduAddr,
int  nBits 
)
virtual

Reads one or more contiguous internal bits (or coil status) from a MODBUS serial device. This method uses the MODBUS function code 0x01 (Read Coils).

Parameters
slaveNo: the address of the slave MODBUS device to query
pduAddr: the relative address of the first bit/coil to read (zero-based)
nBits: the number of bits/coils to read
Returns
a vector of integers, each corresponding to one bit.

On failure, throws an exception or returns an empty array.

Definition at line 1607 of file yocto_serialport.cpp.

vector< int > YSerialPort::modbusReadInputBits ( int  slaveNo,
int  pduAddr,
int  nBits 
)
virtual

Reads one or more contiguous input bits (or discrete inputs) from a MODBUS serial device. This method uses the MODBUS function code 0x02 (Read Discrete Inputs).

Parameters
slaveNo: the address of the slave MODBUS device to query
pduAddr: the relative address of the first bit/input to read (zero-based)
nBits: the number of bits/inputs to read
Returns
a vector of integers, each corresponding to one bit.

On failure, throws an exception or returns an empty array.

Definition at line 1663 of file yocto_serialport.cpp.

vector< int > YSerialPort::modbusReadInputRegisters ( int  slaveNo,
int  pduAddr,
int  nWords 
)
virtual

Reads one or more contiguous input registers (read-only registers) from a MODBUS serial device. This method uses the MODBUS function code 0x04 (Read Input Registers).

Parameters
slaveNo: the address of the slave MODBUS device to query
pduAddr: the relative address of the first input register to read (zero-based)
nWords: the number of input registers to read
Returns
a vector of integers, each corresponding to one 16-bit input value.

On failure, throws an exception or returns an empty array.

Definition at line 1765 of file yocto_serialport.cpp.

vector< int > YSerialPort::modbusReadRegisters ( int  slaveNo,
int  pduAddr,
int  nWords 
)
virtual

Reads one or more contiguous internal registers (holding registers) from a MODBUS serial device. This method uses the MODBUS function code 0x03 (Read Holding Registers).

Parameters
slaveNo: the address of the slave MODBUS device to query
pduAddr: the relative address of the first holding register to read (zero-based)
nWords: the number of holding registers to read
Returns
a vector of integers, each corresponding to one 16-bit register value.

On failure, throws an exception or returns an empty array.

Definition at line 1719 of file yocto_serialport.cpp.

vector< int > YSerialPort::modbusWriteAndReadRegisters ( int  slaveNo,
int  pduWriteAddr,
vector< int >  values,
int  pduReadAddr,
int  nReadWords 
)
virtual

Sets several contiguous internal registers (holding registers) on a MODBUS serial device, then performs a contiguous read of a set of (possibly different) internal registers. This method uses the MODBUS function code 0x17 (Read/Write Multiple Registers).

Parameters
slaveNo: the address of the slave MODBUS device to drive
pduWriteAddr: the relative address of the first internal register to set (zero-based)
values: the vector of 16 bit values to set
pduReadAddr: the relative address of the first internal register to read (zero-based)
nReadWords: the number of 16 bit values to read
Returns
a vector of integers, each corresponding to one 16-bit register value read.

On failure, throws an exception or returns an empty array.

Definition at line 2000 of file yocto_serialport.cpp.

int YSerialPort::modbusWriteBit ( int  slaveNo,
int  pduAddr,
int  value 
)
virtual

Sets a single internal bit (or coil) on a MODBUS serial device. This method uses the MODBUS function code 0x05 (Write Single Coil).

Parameters
slaveNo: the address of the slave MODBUS device to drive
pduAddr: the relative address of the bit/coil to set (zero-based)
value: the value to set (0 for OFF state, non-zero for ON state)
Returns
the number of bits/coils affected on the device (1)

On failure, throws an exception or returns zero.

Definition at line 1811 of file yocto_serialport.cpp.

int YSerialPort::modbusWriteBits ( int  slaveNo,
int  pduAddr,
vector< int >  bits 
)
virtual

Sets several contiguous internal bits (or coils) on a MODBUS serial device. This method uses the MODBUS function code 0x0f (Write Multiple Coils).

Parameters
slaveNo: the address of the slave MODBUS device to drive
pduAddr: the relative address of the first bit/coil to set (zero-based)
bits: the vector of bits to be set (one integer per bit)
Returns
the number of bits/coils affected on the device

On failure, throws an exception or returns zero.

Definition at line 1849 of file yocto_serialport.cpp.

int YSerialPort::modbusWriteRegister ( int  slaveNo,
int  pduAddr,
int  value 
)
virtual

Sets a single internal register (or holding register) on a MODBUS serial device. This method uses the MODBUS function code 0x06 (Write Single Register).

Parameters
slaveNo: the address of the slave MODBUS device to drive
pduAddr: the relative address of the register to set (zero-based)
value: the 16 bit value to set
Returns
the number of registers affected on the device (1)

On failure, throws an exception or returns zero.

Definition at line 1912 of file yocto_serialport.cpp.

int YSerialPort::modbusWriteRegisters ( int  slaveNo,
int  pduAddr,
vector< int >  values 
)
virtual

Sets several contiguous internal registers (or holding registers) on a MODBUS serial device. This method uses the MODBUS function code 0x10 (Write Multiple Registers).

Parameters
slaveNo: the address of the slave MODBUS device to drive
pduAddr: the relative address of the first internal register to set (zero-based)
values: the vector of 16 bit values to set
Returns
the number of registers affected on the device

On failure, throws an exception or returns zero.

Definition at line 1947 of file yocto_serialport.cpp.

YSerialPort* YSerialPort::next ( void  )
inline

Definition at line 943 of file yocto_serialport.h.

YSerialPort * YSerialPort::nextSerialPort ( void  )

Continues the enumeration of serial ports started using yFirstSerialPort().

Returns
a pointer to a YSerialPort object, corresponding to a serial port currently online, or a NULL pointer if there are no more serial ports to enumerate.

Definition at line 2050 of file yocto_serialport.cpp.

string YSerialPort::protocol ( void  )
inline

Definition at line 383 of file yocto_serialport.h.

string YSerialPort::queryLine ( string  query,
int  maxWait 
)
virtual

Sends a text line query to the serial port, and reads the reply, if any. This function is intended to be used when the serial port is configured for 'Line' protocol.

Parameters
query: the line query to send (without CR/LF)
maxWait: the maximum number of milliseconds to wait for a reply.
Returns
the next text line received after sending the text query, as a string. Additional lines can be obtained by calling readLine or readMessages.

On failure, throws an exception or returns an empty array.

Definition at line 1366 of file yocto_serialport.cpp.

vector< int > YSerialPort::queryMODBUS ( int  slaveNo,
vector< int >  pduBytes 
)
virtual

Sends a message to a specified MODBUS slave connected to the serial port, and reads the reply, if any. The message is the PDU, provided as a vector of bytes.

Parameters
slaveNo: the address of the slave MODBUS device to query
pduBytes: the message to send (PDU), as a vector of bytes. The first byte of the PDU is the MODBUS function code.
Returns
the received reply, as a vector of bytes.

On failure, throws an exception or returns an empty array (or a MODBUS error reply).

Definition at line 1532 of file yocto_serialport.cpp.

int YSerialPort::read_avail ( void  )
virtual

Returns the number of bytes available to read in the input buffer starting from the current absolute stream position pointer of the API object.

Returns
the number of bytes available to read

Definition at line 1339 of file yocto_serialport.cpp.

int YSerialPort::read_seek ( int  absPos)
virtual

Changes the current internal stream position to the specified value. This function does not affect the device, it only changes the value stored in the API object for the next read operations.

Parameters
absPos: the absolute position index for next read operations.
Returns
nothing.

Definition at line 1317 of file yocto_serialport.cpp.

int YSerialPort::read_tell ( void  )
virtual

Returns the current absolute stream position pointer of the API object.

Returns
the absolute position index for next read operations.

Definition at line 1328 of file yocto_serialport.cpp.

vector< int > YSerialPort::readArray ( int  nChars)
virtual

Reads data from the receive buffer as a list of bytes, starting at current stream position. If data at current stream position is not available anymore in the receive buffer, the function performs a short read.

Parameters
nChars: the maximum number of bytes to read
Returns
a sequence of bytes with receive buffer contents

On failure, throws an exception or returns a negative error code.

Definition at line 1143 of file yocto_serialport.cpp.

string YSerialPort::readBin ( int  nChars)
virtual

Reads data from the receive buffer as a binary buffer, starting at current stream position. If data at current stream position is not available anymore in the receive buffer, the function performs a short read.

Parameters
nChars: the maximum number of bytes to read
Returns
a binary object with receive buffer contents

On failure, throws an exception or returns a negative error code.

Definition at line 1101 of file yocto_serialport.cpp.

int YSerialPort::readByte ( void  )
virtual

Reads one byte from the receive buffer, starting at current stream position. If data at current stream position is not available anymore in the receive buffer, or if there is no data available yet, the function returns YAPI_NO_MORE_DATA.

Returns
the next byte

On failure, throws an exception or returns a negative error code.

Definition at line 994 of file yocto_serialport.cpp.

string YSerialPort::readHex ( int  nBytes)
virtual

Reads data from the receive buffer as a hexadecimal string, starting at current stream position. If data at current stream position is not available anymore in the receive buffer, the function performs a short read.

Parameters
nBytes: the maximum number of bytes to read
Returns
a string with receive buffer contents, encoded in hexadecimal

On failure, throws an exception or returns a negative error code.

Definition at line 1187 of file yocto_serialport.cpp.

string YSerialPort::readLine ( void  )
virtual

Reads a single line (or message) from the receive buffer, starting at current stream position. This function is intended to be used when the serial port is configured for a message protocol, such as 'Line' mode or frame protocols.

If data at current stream position is not available anymore in the receive buffer, the function returns the oldest available line and moves the stream position just after. If no new full line is received, the function returns an empty line.

Returns
a string with a single line of text

On failure, throws an exception or returns a negative error code.

Definition at line 1235 of file yocto_serialport.cpp.

vector< string > YSerialPort::readMessages ( string  pattern,
int  maxWait 
)
virtual

Searches for incoming messages in the serial port receive buffer matching a given pattern, starting at current position. This function will only compare and return printable characters in the message strings. Binary protocols are handled as hexadecimal strings.

The search returns all messages matching the expression provided as argument in the buffer. If no matching message is found, the search waits for one up to the specified maximum timeout (in milliseconds).

Parameters
pattern: a limited regular expression describing the expected message format, or an empty string if all messages should be returned (no filtering). When using binary protocols, the format applies to the hexadecimal representation of the message.
maxWait: the maximum number of milliseconds to wait for a message if none is found in the receive buffer.
Returns
an array of strings containing the messages found, if any. Binary messages are converted to hexadecimal representation.

On failure, throws an exception or returns an empty array.

Definition at line 1281 of file yocto_serialport.cpp.

string YSerialPort::readStr ( int  nChars)
virtual

Reads data from the receive buffer as a string, starting at current stream position. If data at current stream position is not available anymore in the receive buffer, the function performs a short read.

Parameters
nChars: the maximum number of characters to read
Returns
a string with receive buffer contents

On failure, throws an exception or returns a negative error code.

Definition at line 1065 of file yocto_serialport.cpp.

int YSerialPort::registerValueCallback ( YSerialPortValueCallback  callback)
virtual

Registers the callback function that is invoked on every change of advertised value. The callback is invoked only during the execution of ySleep or yHandleEvents. This provides control over the time when the callback is triggered. For good responsiveness, remember to call one of these two functions periodically. To unregister a callback, pass a NULL pointer as argument.

Parameters
callback: the callback function to call, or a NULL pointer. The callback function should take two arguments: the function object of which the value has changed, and the character string describing the new advertised value.

Definition at line 771 of file yocto_serialport.cpp.

int YSerialPort::reset ( void  )
virtual

Clears the serial port buffer and resets counters to zero.

Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 812 of file yocto_serialport.cpp.

int YSerialPort::rxCount ( void  )
inline

Definition at line 207 of file yocto_serialport.h.

int YSerialPort::rxMsgCount ( void  )
inline

Definition at line 243 of file yocto_serialport.h.

int YSerialPort::selectJob ( string  jobfile)
virtual

Load and start processing the specified job file. The file must have been previously created using the user interface or uploaded on the device filesystem using the uploadJob() function.

Parameters
jobfile: name of the job file (on the device filesystem)
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 1419 of file yocto_serialport.cpp.

int YSerialPort::sendCommand ( string  text)
virtual

Definition at line 800 of file yocto_serialport.cpp.

string YSerialPort::serialMode ( void  )
inline

Definition at line 424 of file yocto_serialport.h.

int YSerialPort::set_command ( const string &  newval)

Definition at line 496 of file yocto_serialport.cpp.

int YSerialPort::set_currentJob ( const string &  newval)

Changes the job to use when the device is powered on. Remember to call the saveToFlash() method of the module if the modification must be kept.

Parameters
newval: a string corresponding to the job to use when the device is powered on
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 402 of file yocto_serialport.cpp.

int YSerialPort::set_protocol ( const string &  newval)

Changes the type of protocol used over the serial line. Possible values are "Line" for ASCII messages separated by CR and/or LF, "Frame:[timeout]ms" for binary messages separated by a delay time, "Modbus-ASCII" for MODBUS messages in ASCII mode, "Modbus-RTU" for MODBUS messages in RTU mode, "Wiegand-ASCII" for Wiegand messages in ASCII mode, "Wiegand-26","Wiegand-34", etc for Wiegand messages in byte mode, "Char" for a continuous ASCII stream or "Byte" for a continuous binary stream. The suffix "/[wait]ms" can be added to reduce the transmit rate so that there is always at lest the specified number of milliseconds between each bytes sent.

Parameters
newval: a string corresponding to the type of protocol used over the serial line
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 630 of file yocto_serialport.cpp.

int YSerialPort::set_RTS ( int  val)
virtual

Manually sets the state of the RTS line. This function has no effect when hardware handshake is enabled, as the RTS line is driven automatically.

Parameters
val: 1 to turn RTS on, 0 to turn RTS off
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 1434 of file yocto_serialport.cpp.

int YSerialPort::set_serialMode ( const string &  newval)

Changes the serial port communication parameters, with a string such as "9600,8N1". The string includes the baud rate, the number of data bits, the parity, and the number of stop bits. An optional suffix can be added to enable flow control: "CtsRts" for hardware handshake, "XOnXOff" for logical flow control and "Simplex" for acquiring a shared bus using the RTS line (as used by some RS485 adapters for instance).

Parameters
newval: a string corresponding to the serial port communication parameters, with a string such as "9600,8N1"
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 696 of file yocto_serialport.cpp.

int YSerialPort::set_startupJob ( const string &  newval)

Changes the job to use when the device is powered on. Remember to call the saveToFlash() method of the module if the modification must be kept.

Parameters
newval: a string corresponding to the job to use when the device is powered on
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 458 of file yocto_serialport.cpp.

int YSerialPort::set_voltageLevel ( Y_VOLTAGELEVEL_enum  newval)

Changes the voltage type used on the serial line. Valid values will depend on the Yoctopuce device model featuring the serial port feature. Check your device documentation to find out which values are valid for that specific model. Trying to set an invalid value will have no effect.

Parameters
newval: a value among Y_VOLTAGELEVEL_OFF, Y_VOLTAGELEVEL_TTL3V, Y_VOLTAGELEVEL_TTL3VR, Y_VOLTAGELEVEL_TTL5V, Y_VOLTAGELEVEL_TTL5VR, Y_VOLTAGELEVEL_RS232 and Y_VOLTAGELEVEL_RS485 corresponding to the voltage type used on the serial line
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 558 of file yocto_serialport.cpp.

int YSerialPort::setCommand ( const string &  newval)
inline

Definition at line 330 of file yocto_serialport.h.

int YSerialPort::setCurrentJob ( const string &  newval)
inline

Definition at line 294 of file yocto_serialport.h.

int YSerialPort::setProtocol ( const string &  newval)
inline

Definition at line 406 of file yocto_serialport.h.

int YSerialPort::setSerialMode ( const string &  newval)
inline

Definition at line 443 of file yocto_serialport.h.

int YSerialPort::setStartupJob ( const string &  newval)
inline

Definition at line 321 of file yocto_serialport.h.

int YSerialPort::setVoltageLevel ( Y_VOLTAGELEVEL_enum  newval)
inline

Definition at line 363 of file yocto_serialport.h.

vector< YSnoopingRecord > YSerialPort::snoopMessages ( int  maxWait)
virtual

Retrieves messages (both direction) in the serial port buffer, starting at current position. This function will only compare and return printable characters in the message strings. Binary protocols are handled as hexadecimal strings.

If no message is found, the search waits for one up to the specified maximum timeout (in milliseconds).

Parameters
maxWait: the maximum number of milliseconds to wait for a message if none is found in the receive buffer.
Returns
an array of YSnoopingRecord objects containing the messages found, if any. Binary messages are converted to hexadecimal representation.

On failure, throws an exception or returns an empty array.

Definition at line 1477 of file yocto_serialport.cpp.

string YSerialPort::startupJob ( void  )
inline

Definition at line 306 of file yocto_serialport.h.

int YSerialPort::txCount ( void  )
inline

Definition at line 219 of file yocto_serialport.h.

int YSerialPort::txMsgCount ( void  )
inline

Definition at line 255 of file yocto_serialport.h.

int YSerialPort::uploadJob ( string  jobfile,
string  jsonDef 
)
virtual

Saves the job definition string (JSON data) into a job file. The job file can be later enabled using selectJob().

Parameters
jobfile: name of the job file to save on the device filesystem
jsonDef: a string containing a JSON definition of the job
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 1402 of file yocto_serialport.cpp.

Y_VOLTAGELEVEL_enum YSerialPort::voltageLevel ( void  )
inline

Definition at line 344 of file yocto_serialport.h.

int YSerialPort::writeArray ( vector< int >  byteList)
virtual

Sends a byte sequence (provided as a list of bytes) to the serial port.

Parameters
byteList: a list of byte codes
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 895 of file yocto_serialport.cpp.

int YSerialPort::writeBin ( string  buff)
virtual

Sends a binary buffer to the serial port, as is.

Parameters
buff: the binary buffer to send
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 881 of file yocto_serialport.cpp.

int YSerialPort::writeByte ( int  code)
virtual

Sends a single byte to the serial port.

Parameters
code: the byte to send
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 830 of file yocto_serialport.cpp.

int YSerialPort::writeHex ( string  hexString)
virtual

Sends a byte sequence (provided as a hexadecimal string) to the serial port.

Parameters
hexString: a string of hexadecimal byte codes
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 924 of file yocto_serialport.cpp.

int YSerialPort::writeLine ( string  text)
virtual

Sends an ASCII string to the serial port, followed by a line break (CR LF).

Parameters
text: the text string to send
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 957 of file yocto_serialport.cpp.

int YSerialPort::writeMODBUS ( string  hexString)
virtual

Sends a MODBUS message (provided as a hexadecimal string) to the serial port. The message must start with the slave address. The MODBUS CRC/LRC is automatically added by the function. This function does not wait for a reply.

Parameters
hexString: a hexadecimal message string, including device address but no CRC/LRC
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 1515 of file yocto_serialport.cpp.

int YSerialPort::writeStr ( string  text)
virtual

Sends an ASCII string to the serial port, as is.

Parameters
text: the text string to send
Returns
YAPI_SUCCESS if the call succeeds.

On failure, throws an exception or returns a negative error code.

Definition at line 844 of file yocto_serialport.cpp.

Friends And Related Function Documentation

YSerialPort* yFindSerialPort ( const string &  func)
friend

Retrieves a serial port for a given identifier. The identifier can be specified using several formats:

  • FunctionLogicalName
  • ModuleSerialNumber.FunctionIdentifier
  • ModuleSerialNumber.FunctionLogicalName
  • ModuleLogicalName.FunctionIdentifier
  • ModuleLogicalName.FunctionLogicalName

This function does not require that the serial port is online at the time it is invoked. The returned object is nevertheless valid. Use the method YSerialPort.isOnline() to test if the serial port is indeed online at a given time. In case of ambiguity when looking for a serial port by logical name, no error is notified: the first instance found is returned. The search is performed first by hardware name, then by logical name.

If a call to this object's is_online() method returns FALSE although you are certain that the matching device is plugged, make sure that you did call registerHub() at application initialization time.

Parameters
func: a string that uniquely characterizes the serial port
Returns
a YSerialPort object allowing you to drive the serial port.

Definition at line 993 of file yocto_serialport.h.

YSerialPort* yFirstSerialPort ( void  )
friend

Starts the enumeration of serial ports currently accessible. Use the method YSerialPort.nextSerialPort() to iterate on next serial ports.

Returns
a pointer to a YSerialPort object, corresponding to the first serial port currently online, or a NULL pointer if there are none.

Definition at line 1004 of file yocto_serialport.h.

Member Data Documentation

string YSerialPort::_command
protected

Definition at line 155 of file yocto_serialport.h.

string YSerialPort::_currentJob
protected

Definition at line 153 of file yocto_serialport.h.

int YSerialPort::_errCount
protected

Definition at line 149 of file yocto_serialport.h.

string YSerialPort::_lastMsg
protected

Definition at line 152 of file yocto_serialport.h.

string YSerialPort::_protocol
protected

Definition at line 157 of file yocto_serialport.h.

string YSerialPort::_rxbuff
protected

Definition at line 161 of file yocto_serialport.h.

int YSerialPort::_rxbuffptr
protected

Definition at line 162 of file yocto_serialport.h.

int YSerialPort::_rxCount
protected

Definition at line 147 of file yocto_serialport.h.

int YSerialPort::_rxMsgCount
protected

Definition at line 150 of file yocto_serialport.h.

int YSerialPort::_rxptr
protected

Definition at line 160 of file yocto_serialport.h.

string YSerialPort::_serialMode
protected

Definition at line 158 of file yocto_serialport.h.

string YSerialPort::_startupJob
protected

Definition at line 154 of file yocto_serialport.h.

int YSerialPort::_txCount
protected

Definition at line 148 of file yocto_serialport.h.

int YSerialPort::_txMsgCount
protected

Definition at line 151 of file yocto_serialport.h.

YSerialPortValueCallback YSerialPort::_valueCallbackSerialPort
protected

Definition at line 159 of file yocto_serialport.h.

Y_VOLTAGELEVEL_enum YSerialPort::_voltageLevel
protected

Definition at line 156 of file yocto_serialport.h.

const string YSerialPort::COMMAND_INVALID = YAPI_INVALID_STRING
static

Definition at line 186 of file yocto_serialport.h.

const string YSerialPort::CURRENTJOB_INVALID = YAPI_INVALID_STRING
static

Definition at line 184 of file yocto_serialport.h.

const int YSerialPort::ERRCOUNT_INVALID = YAPI_INVALID_UINT
static

Definition at line 180 of file yocto_serialport.h.

const string YSerialPort::LASTMSG_INVALID = YAPI_INVALID_STRING
static

Definition at line 183 of file yocto_serialport.h.

const string YSerialPort::PROTOCOL_INVALID = YAPI_INVALID_STRING
static

Definition at line 195 of file yocto_serialport.h.

const int YSerialPort::RXCOUNT_INVALID = YAPI_INVALID_UINT
static

Definition at line 178 of file yocto_serialport.h.

const int YSerialPort::RXMSGCOUNT_INVALID = YAPI_INVALID_UINT
static

Definition at line 181 of file yocto_serialport.h.

const string YSerialPort::SERIALMODE_INVALID = YAPI_INVALID_STRING
static

Definition at line 196 of file yocto_serialport.h.

const string YSerialPort::STARTUPJOB_INVALID = YAPI_INVALID_STRING
static

Definition at line 185 of file yocto_serialport.h.

const int YSerialPort::TXCOUNT_INVALID = YAPI_INVALID_UINT
static

Definition at line 179 of file yocto_serialport.h.

const int YSerialPort::TXMSGCOUNT_INVALID = YAPI_INVALID_UINT
static

Definition at line 182 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_INVALID = Y_VOLTAGELEVEL_INVALID
static

Definition at line 194 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_OFF = Y_VOLTAGELEVEL_OFF
static

Definition at line 187 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_RS232 = Y_VOLTAGELEVEL_RS232
static

Definition at line 192 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_RS485 = Y_VOLTAGELEVEL_RS485
static

Definition at line 193 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_TTL3V = Y_VOLTAGELEVEL_TTL3V
static

Definition at line 188 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_TTL3VR = Y_VOLTAGELEVEL_TTL3VR
static

Definition at line 189 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_TTL5V = Y_VOLTAGELEVEL_TTL5V
static

Definition at line 190 of file yocto_serialport.h.

const Y_VOLTAGELEVEL_enum YSerialPort::VOLTAGELEVEL_TTL5VR = Y_VOLTAGELEVEL_TTL5VR
static

Definition at line 191 of file yocto_serialport.h.


The documentation for this class was generated from the following files:


yoctopuce_altimeter
Author(s): Anja Sheppard
autogenerated on Mon Jun 10 2019 15:49:14