remote node
This commit is contained in:
parent
2aad45e19d
commit
a8c7ca1cae
@ -7,6 +7,7 @@
|
||||
"external_net_port": 19683,
|
||||
"mqtt_user": "zxwl",
|
||||
"mqtt_password": "zxwl1234@",
|
||||
"pub_gps_topic": "/zxwl/vehicle/V060002/gps"
|
||||
"pub_gps_topic": "/zxwl/vehicle/V060002/gps",
|
||||
"remote_topic": "/zxwl/vehicle/V060002/ctrl"
|
||||
}
|
||||
}
|
||||
64
src/remote/CMakeLists.txt
Normal file
64
src/remote/CMakeLists.txt
Normal file
@ -0,0 +1,64 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(remote)
|
||||
|
||||
# Default to C99
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
endif()
|
||||
|
||||
# Default to C++14
|
||||
if(NOT CMAKE_CXX_STANDARD)
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
endif()
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(std_msgs REQUIRED)
|
||||
find_package(sweeper_interfaces REQUIRED)
|
||||
|
||||
include_directories(
|
||||
include/remote
|
||||
include/paho_mqtt_3c
|
||||
)
|
||||
|
||||
add_executable(remote_node
|
||||
src/remote_node.cpp
|
||||
src/jsoncpp.cpp
|
||||
)
|
||||
|
||||
ament_target_dependencies(remote_node rclcpp std_msgs sweeper_interfaces)
|
||||
|
||||
if(CMAKE_SYSTEM_PROCESSOR MATCHES aarch64)
|
||||
target_link_libraries(
|
||||
remote_node
|
||||
${PROJECT_SOURCE_DIR}/lib/libpaho-mqtt3c-static.a
|
||||
)
|
||||
else()
|
||||
target_link_libraries(
|
||||
remote_node
|
||||
${PROJECT_SOURCE_DIR}/lib/libpaho-mqtt3c.a
|
||||
)
|
||||
endif()
|
||||
|
||||
install(TARGETS
|
||||
remote_node
|
||||
DESTINATION lib/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# uncomment the line when a copyright and license is not present in all source files
|
||||
#set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# uncomment the line when this package is not in a git repo
|
||||
#set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
ament_package()
|
||||
83
src/remote/include/paho_mqtt_3c/Base64.h
Normal file
83
src/remote/include/paho_mqtt_3c/Base64.h
Normal file
@ -0,0 +1,83 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2018 Wind River Systems, Inc. All Rights Reserved.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Keith Holman - initial implementation and documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(BASE64_H)
|
||||
#define BASE64_H
|
||||
|
||||
/** type for size of a buffer, it saves passing around @p size_t (unsigned long long or unsigned long int) */
|
||||
typedef unsigned int b64_size_t;
|
||||
/** type for raw base64 data */
|
||||
typedef unsigned char b64_data_t;
|
||||
|
||||
/**
|
||||
* Decodes base64 data
|
||||
*
|
||||
* @param[out] out decoded data
|
||||
* @param[in] out_len length of output buffer
|
||||
* @param[in] in base64 string to decode
|
||||
* @param[in] in_len length of input buffer
|
||||
*
|
||||
* @return the amount of data decoded
|
||||
*
|
||||
* @see Base64_decodeLength
|
||||
* @see Base64_encode
|
||||
*/
|
||||
b64_size_t Base64_decode( b64_data_t *out, b64_size_t out_len,
|
||||
const char *in, b64_size_t in_len );
|
||||
|
||||
/**
|
||||
* Size of buffer required to decode base64 data
|
||||
*
|
||||
* @param[in] in base64 string to decode
|
||||
* @param[in] in_len length of input buffer
|
||||
*
|
||||
* @return the size of buffer the decoded string would require
|
||||
*
|
||||
* @see Base64_decode
|
||||
* @see Base64_encodeLength
|
||||
*/
|
||||
b64_size_t Base64_decodeLength( const char *in, b64_size_t in_len );
|
||||
|
||||
/**
|
||||
* Encodes base64 data
|
||||
*
|
||||
* @param[out] out encode base64 string
|
||||
* @param[in] out_len length of output buffer
|
||||
* @param[in] in raw data to encode
|
||||
* @param[in] in_len length of input buffer
|
||||
*
|
||||
* @return the amount of data encoded
|
||||
*
|
||||
* @see Base64_decode
|
||||
* @see Base64_encodeLength
|
||||
*/
|
||||
b64_size_t Base64_encode( char *out, b64_size_t out_len,
|
||||
const b64_data_t *in, b64_size_t in_len );
|
||||
|
||||
/**
|
||||
* Size of buffer required to encode base64 data
|
||||
*
|
||||
* @param[in] in raw data to encode
|
||||
* @param[in] in_len length of input buffer
|
||||
*
|
||||
* @return the size of buffer the encoded string would require
|
||||
*
|
||||
* @see Base64_decodeLength
|
||||
* @see Base64_encode
|
||||
*/
|
||||
b64_size_t Base64_encodeLength( const b64_data_t *in, b64_size_t in_len );
|
||||
|
||||
#endif /* BASE64_H */
|
||||
153
src/remote/include/paho_mqtt_3c/Clients.h
Normal file
153
src/remote/include/paho_mqtt_3c/Clients.h
Normal file
@ -0,0 +1,153 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - add SSL support
|
||||
* Ian Craggs - fix for bug 413429 - connectionLost not called
|
||||
* Ian Craggs - change will payload to binary
|
||||
* Ian Craggs - password to binary
|
||||
* Ian Craggs - MQTT 5 support
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(CLIENTS_H)
|
||||
#define CLIENTS_H
|
||||
|
||||
#include <time.h>
|
||||
#if defined(OPENSSL)
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#include <winsock2.h>
|
||||
#endif
|
||||
#include <openssl/ssl.h>
|
||||
#endif
|
||||
#include "MQTTClient.h"
|
||||
#include "LinkedList.h"
|
||||
#include "MQTTClientPersistence.h"
|
||||
|
||||
|
||||
/**
|
||||
* Stored publication data to minimize copying
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
char *topic;
|
||||
int topiclen;
|
||||
char* payload;
|
||||
int payloadlen;
|
||||
int refcount;
|
||||
} Publications;
|
||||
|
||||
/**
|
||||
* Client publication message data
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
int qos;
|
||||
int retain;
|
||||
int msgid;
|
||||
int MQTTVersion;
|
||||
MQTTProperties properties;
|
||||
Publications *publish;
|
||||
time_t lastTouch; /**> used for retry and expiry */
|
||||
char nextMessageType; /**> PUBREC, PUBREL, PUBCOMP */
|
||||
int len; /**> length of the whole structure+data */
|
||||
} Messages;
|
||||
|
||||
/**
|
||||
* Client will message data
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
char *topic;
|
||||
int payloadlen;
|
||||
void *payload;
|
||||
int retained;
|
||||
int qos;
|
||||
} willMessages;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int socket;
|
||||
time_t lastSent;
|
||||
time_t lastReceived;
|
||||
#if defined(OPENSSL)
|
||||
SSL* ssl;
|
||||
SSL_CTX* ctx;
|
||||
#endif
|
||||
int websocket; /**< socket has been upgraded to use web sockets */
|
||||
char *websocket_key;
|
||||
} networkHandles;
|
||||
|
||||
|
||||
/* connection states */
|
||||
/** no connection in progress, see connected value */
|
||||
#define NOT_IN_PROGRESS 0x0
|
||||
/** TCP connection in progress */
|
||||
#define TCP_IN_PROGRESS 0x1
|
||||
/** SSL connection in progress */
|
||||
#define SSL_IN_PROGRESS 0x2
|
||||
/** Websocket connection in progress */
|
||||
#define WEBSOCKET_IN_PROGRESS 0x3
|
||||
/** TCP completed, waiting for MQTT ACK */
|
||||
#define WAIT_FOR_CONNACK 0x4
|
||||
/** Disconnecting */
|
||||
#define DISCONNECTING -2
|
||||
|
||||
/**
|
||||
* Data related to one client
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
char* clientID; /**< the string id of the client */
|
||||
const char* username; /**< MQTT v3.1 user name */
|
||||
int passwordlen; /**< MQTT password length */
|
||||
const void* password; /**< MQTT v3.1 binary password */
|
||||
unsigned int cleansession : 1; /**< MQTT V3 clean session flag */
|
||||
unsigned int cleanstart : 1; /**< MQTT V5 clean start flag */
|
||||
unsigned int connected : 1; /**< whether it is currently connected */
|
||||
unsigned int good : 1; /**< if we have an error on the socket we turn this off */
|
||||
unsigned int ping_outstanding : 1;
|
||||
signed int connect_state : 4;
|
||||
networkHandles net;
|
||||
int msgID;
|
||||
int keepAliveInterval;
|
||||
int retryInterval;
|
||||
int maxInflightMessages;
|
||||
willMessages* will;
|
||||
List* inboundMsgs;
|
||||
List* outboundMsgs; /**< in flight */
|
||||
List* messageQueue;
|
||||
unsigned int qentry_seqno;
|
||||
void* phandle; /* the persistence handle */
|
||||
MQTTClient_persistence* persistence; /* a persistence implementation */
|
||||
void* context; /* calling context - used when calling disconnect_internal */
|
||||
int MQTTVersion;
|
||||
int sessionExpiry; /**< MQTT 5 session expiry */
|
||||
#if defined(OPENSSL)
|
||||
MQTTClient_SSLOptions *sslopts;
|
||||
SSL_SESSION* session; /***< SSL session pointer for fast handhake */
|
||||
#endif
|
||||
} Clients;
|
||||
|
||||
int clientIDCompare(void* a, void* b);
|
||||
int clientSocketCompare(void* a, void* b);
|
||||
|
||||
/**
|
||||
* Configuration data related to all clients
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
const char* version;
|
||||
List* clients;
|
||||
} ClientStates;
|
||||
|
||||
#endif
|
||||
82
src/remote/include/paho_mqtt_3c/Heap.h
Normal file
82
src/remote/include/paho_mqtt_3c/Heap.h
Normal file
@ -0,0 +1,82 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2013 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - use tree data structure instead of list
|
||||
*******************************************************************************/
|
||||
|
||||
|
||||
#if !defined(HEAP_H)
|
||||
#define HEAP_H
|
||||
|
||||
#if defined(HIGH_PERFORMANCE)
|
||||
#define NO_HEAP_TRACKING 1
|
||||
#endif
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#if !defined(NO_HEAP_TRACKING)
|
||||
/**
|
||||
* redefines malloc to use "mymalloc" so that heap allocation can be tracked
|
||||
* @param x the size of the item to be allocated
|
||||
* @return the pointer to the item allocated, or NULL
|
||||
*/
|
||||
#define malloc(x) mymalloc(__FILE__, __LINE__, x)
|
||||
|
||||
/**
|
||||
* redefines realloc to use "myrealloc" so that heap allocation can be tracked
|
||||
* @param a the heap item to be reallocated
|
||||
* @param b the new size of the item
|
||||
* @return the new pointer to the heap item
|
||||
*/
|
||||
#define realloc(a, b) myrealloc(__FILE__, __LINE__, a, b)
|
||||
|
||||
/**
|
||||
* redefines free to use "myfree" so that heap allocation can be tracked
|
||||
* @param x the size of the item to be freed
|
||||
*/
|
||||
#define free(x) myfree(__FILE__, __LINE__, x)
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Information about the state of the heap.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
size_t current_size; /**< current size of the heap in bytes */
|
||||
size_t max_size; /**< max size the heap has reached in bytes */
|
||||
} heap_info;
|
||||
|
||||
#if defined(__cplusplus)
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
void* mymalloc(char*, int, size_t size);
|
||||
void* myrealloc(char*, int, void* p, size_t size);
|
||||
void myfree(char*, int, void* p);
|
||||
|
||||
void Heap_scan(FILE* file);
|
||||
int Heap_initialize(void);
|
||||
void Heap_terminate(void);
|
||||
heap_info* Heap_get_info(void);
|
||||
int HeapDump(FILE* file);
|
||||
int HeapDumpString(FILE* file, char* str);
|
||||
void* Heap_findItem(void* p);
|
||||
void Heap_unlink(char* file, int line, void* p);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
105
src/remote/include/paho_mqtt_3c/LinkedList.h
Normal file
105
src/remote/include/paho_mqtt_3c/LinkedList.h
Normal file
@ -0,0 +1,105 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2013 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - updates for the async client
|
||||
* Ian Craggs - change size types from int to size_t
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(LINKEDLIST_H)
|
||||
#define LINKEDLIST_H
|
||||
|
||||
#include <stdlib.h> /* for size_t definition */
|
||||
|
||||
/*BE
|
||||
defm defList(T)
|
||||
|
||||
def T concat Item
|
||||
{
|
||||
at 4
|
||||
n32 ptr T concat Item suppress "next"
|
||||
at 0
|
||||
n32 ptr T concat Item suppress "prev"
|
||||
at 8
|
||||
n32 ptr T id2str(T)
|
||||
}
|
||||
|
||||
def T concat List
|
||||
{
|
||||
n32 ptr T concat Item suppress "first"
|
||||
n32 ptr T concat Item suppress "last"
|
||||
n32 ptr T concat Item suppress "current"
|
||||
n32 dec "count"
|
||||
n32 suppress "size"
|
||||
}
|
||||
endm
|
||||
|
||||
defList(INT)
|
||||
defList(STRING)
|
||||
defList(TMP)
|
||||
|
||||
BE*/
|
||||
|
||||
/**
|
||||
* Structure to hold all data for one list element
|
||||
*/
|
||||
typedef struct ListElementStruct
|
||||
{
|
||||
struct ListElementStruct *prev, /**< pointer to previous list element */
|
||||
*next; /**< pointer to next list element */
|
||||
void* content; /**< pointer to element content */
|
||||
} ListElement;
|
||||
|
||||
|
||||
/**
|
||||
* Structure to hold all data for one list
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
ListElement *first, /**< first element in the list */
|
||||
*last, /**< last element in the list */
|
||||
*current; /**< current element in the list, for iteration */
|
||||
int count; /**< no of items */
|
||||
size_t size; /**< heap storage used */
|
||||
} List;
|
||||
|
||||
void ListZero(List*);
|
||||
List* ListInitialize(void);
|
||||
|
||||
void ListAppend(List* aList, void* content, size_t size);
|
||||
void ListAppendNoMalloc(List* aList, void* content, ListElement* newel, size_t size);
|
||||
void ListInsert(List* aList, void* content, size_t size, ListElement* index);
|
||||
|
||||
int ListRemove(List* aList, void* content);
|
||||
int ListRemoveItem(List* aList, void* content, int(*callback)(void*, void*));
|
||||
void* ListDetachHead(List* aList);
|
||||
int ListRemoveHead(List* aList);
|
||||
void* ListPopTail(List* aList);
|
||||
|
||||
int ListDetach(List* aList, void* content);
|
||||
int ListDetachItem(List* aList, void* content, int(*callback)(void*, void*));
|
||||
|
||||
void ListFree(List* aList);
|
||||
void ListEmpty(List* aList);
|
||||
void ListFreeNoContent(List* aList);
|
||||
|
||||
ListElement* ListNextElement(List* aList, ListElement** pos);
|
||||
ListElement* ListPrevElement(List* aList, ListElement** pos);
|
||||
|
||||
ListElement* ListFind(List* aList, void* content);
|
||||
ListElement* ListFindItem(List* aList, void* content, int(*callback)(void*, void*));
|
||||
|
||||
int intcompare(void* a, void* b);
|
||||
int stringcompare(void* a, void* b);
|
||||
|
||||
#endif
|
||||
85
src/remote/include/paho_mqtt_3c/Log.h
Normal file
85
src/remote/include/paho_mqtt_3c/Log.h
Normal file
@ -0,0 +1,85 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2013 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - updates for the async client
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(LOG_H)
|
||||
#define LOG_H
|
||||
|
||||
/*BE
|
||||
map LOG_LEVELS
|
||||
{
|
||||
"TRACE_MAXIMUM" 1
|
||||
"TRACE_MEDIUM" 2
|
||||
"TRACE_MINIMUM" 3
|
||||
"TRACE_PROTOCOL" 4
|
||||
|
||||
"ERROR" 5
|
||||
"SEVERE" 6
|
||||
"FATAL" 7
|
||||
}
|
||||
BE*/
|
||||
|
||||
enum LOG_LEVELS {
|
||||
INVALID_LEVEL = -1,
|
||||
TRACE_MAXIMUM = 1,
|
||||
TRACE_MEDIUM,
|
||||
TRACE_MINIMUM,
|
||||
TRACE_PROTOCOL,
|
||||
LOG_ERROR,
|
||||
LOG_SEVERE,
|
||||
LOG_FATAL,
|
||||
};
|
||||
|
||||
|
||||
/*BE
|
||||
def trace_settings_type
|
||||
{
|
||||
n32 map LOG_LEVELS "trace_level"
|
||||
n32 dec "max_trace_entries"
|
||||
n32 dec "trace_output_level"
|
||||
}
|
||||
BE*/
|
||||
typedef struct
|
||||
{
|
||||
enum LOG_LEVELS trace_level; /**< trace level */
|
||||
int max_trace_entries; /**< max no of entries in the trace buffer */
|
||||
enum LOG_LEVELS trace_output_level; /**< trace level to output to destination */
|
||||
} trace_settings_type;
|
||||
|
||||
extern trace_settings_type trace_settings;
|
||||
|
||||
#define LOG_PROTOCOL TRACE_PROTOCOL
|
||||
#define TRACE_MAX TRACE_MAXIMUM
|
||||
#define TRACE_MIN TRACE_MINIMUM
|
||||
#define TRACE_MED TRACE_MEDIUM
|
||||
|
||||
typedef struct
|
||||
{
|
||||
const char* name;
|
||||
const char* value;
|
||||
} Log_nameValue;
|
||||
|
||||
int Log_initialize(Log_nameValue*);
|
||||
void Log_terminate(void);
|
||||
|
||||
void Log(enum LOG_LEVELS, int, const char *, ...);
|
||||
void Log_stackTrace(enum LOG_LEVELS, int, int, int, const char*, int, int*);
|
||||
|
||||
typedef void Log_traceCallback(enum LOG_LEVELS level, const char *message);
|
||||
void Log_setTraceCallback(Log_traceCallback* callback);
|
||||
void Log_setTraceLevel(enum LOG_LEVELS level);
|
||||
|
||||
#endif
|
||||
2068
src/remote/include/paho_mqtt_3c/MQTTAsync.h
Normal file
2068
src/remote/include/paho_mqtt_3c/MQTTAsync.h
Normal file
File diff suppressed because it is too large
Load Diff
1670
src/remote/include/paho_mqtt_3c/MQTTClient.h
Normal file
1670
src/remote/include/paho_mqtt_3c/MQTTClient.h
Normal file
File diff suppressed because it is too large
Load Diff
254
src/remote/include/paho_mqtt_3c/MQTTClientPersistence.h
Normal file
254
src/remote/include/paho_mqtt_3c/MQTTClientPersistence.h
Normal file
@ -0,0 +1,254 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2012 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
/**
|
||||
* @file
|
||||
* \brief This structure represents a persistent data store, used to store
|
||||
* outbound and inbound messages, in order to achieve reliable messaging.
|
||||
*
|
||||
* The MQTT Client persists QoS1 and QoS2 messages in order to meet the
|
||||
* assurances of delivery associated with these @ref qos levels. The messages
|
||||
* are saved in persistent storage
|
||||
* The type and context of the persistence implementation are specified when
|
||||
* the MQTT client is created (see MQTTClient_create()). The default
|
||||
* persistence type (::MQTTCLIENT_PERSISTENCE_DEFAULT) uses a file system-based
|
||||
* persistence mechanism. The <i>persistence_context</i> argument passed to
|
||||
* MQTTClient_create() when using the default peristence is a string
|
||||
* representing the location of the persistence directory. If the context
|
||||
* argument is NULL, the working directory will be used.
|
||||
*
|
||||
* To use memory-based persistence, an application passes
|
||||
* ::MQTTCLIENT_PERSISTENCE_NONE as the <i>persistence_type</i> to
|
||||
* MQTTClient_create(). This can lead to message loss in certain situations,
|
||||
* but can be appropriate in some cases (see @ref qos).
|
||||
*
|
||||
* Client applications can provide their own persistence mechanism by passing
|
||||
* ::MQTTCLIENT_PERSISTENCE_USER as the <i>persistence_type</i>. To implement a
|
||||
* custom persistence mechanism, the application must pass an initialized
|
||||
* ::MQTTClient_persistence structure as the <i>persistence_context</i>
|
||||
* argument to MQTTClient_create().
|
||||
*
|
||||
* If the functions defined return an ::MQTTCLIENT_PERSISTENCE_ERROR then the
|
||||
* state of the persisted data should remain as it was prior to the function
|
||||
* being called. For example, if Persistence_put() returns
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR, then it is assumed tha tthe persistent store
|
||||
* does not contain the data that was passed to the function. Similarly, if
|
||||
* Persistence_remove() returns ::MQTTCLIENT_PERSISTENCE_ERROR then it is
|
||||
* assumed that the data to be removed is still held in the persistent store.
|
||||
*
|
||||
* It is up to the persistence implementation to log any error information that
|
||||
* may be required to diagnose a persistence mechanism failure.
|
||||
*/
|
||||
|
||||
/*
|
||||
/// @cond EXCLUDE
|
||||
*/
|
||||
#if !defined(MQTTCLIENTPERSISTENCE_H)
|
||||
#define MQTTCLIENTPERSISTENCE_H
|
||||
/*
|
||||
/// @endcond
|
||||
*/
|
||||
|
||||
/**
|
||||
* This <i>persistence_type</i> value specifies the default file system-based
|
||||
* persistence mechanism (see MQTTClient_create()).
|
||||
*/
|
||||
#define MQTTCLIENT_PERSISTENCE_DEFAULT 0
|
||||
/**
|
||||
* This <i>persistence_type</i> value specifies a memory-based
|
||||
* persistence mechanism (see MQTTClient_create()).
|
||||
*/
|
||||
#define MQTTCLIENT_PERSISTENCE_NONE 1
|
||||
/**
|
||||
* This <i>persistence_type</i> value specifies an application-specific
|
||||
* persistence mechanism (see MQTTClient_create()).
|
||||
*/
|
||||
#define MQTTCLIENT_PERSISTENCE_USER 2
|
||||
|
||||
/**
|
||||
* Application-specific persistence functions must return this error code if
|
||||
* there is a problem executing the function.
|
||||
*/
|
||||
#define MQTTCLIENT_PERSISTENCE_ERROR -2
|
||||
|
||||
/**
|
||||
* @brief Initialize the persistent store.
|
||||
*
|
||||
* Either open the existing persistent store for this client ID or create a new
|
||||
* one if one doesn't exist. If the persistent store is already open, return
|
||||
* without taking any action.
|
||||
*
|
||||
* An application can use the same client identifier to connect to many
|
||||
* different servers. The <i>clientid</i> in conjunction with the
|
||||
* <i>serverURI</i> uniquely identifies the persistence store required.
|
||||
*
|
||||
* @param handle The address of a pointer to a handle for this persistence
|
||||
* implementation. This function must set handle to a valid reference to the
|
||||
* persistence following a successful return.
|
||||
* The handle pointer is passed as an argument to all the other
|
||||
* persistence functions. It may include the context parameter and/or any other
|
||||
* data for use by the persistence functions.
|
||||
* @param clientID The client identifier for which the persistent store should
|
||||
* be opened.
|
||||
* @param serverURI The connection string specified when the MQTT client was
|
||||
* created (see MQTTClient_create()).
|
||||
* @param context A pointer to any data required to initialize the persistent
|
||||
* store (see ::MQTTClient_persistence).
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_open)(void** handle, const char* clientID, const char* serverURI, void* context);
|
||||
|
||||
/**
|
||||
* @brief Close the persistent store referred to by the handle.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_close)(void* handle);
|
||||
|
||||
/**
|
||||
* @brief Put the specified data into the persistent store.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @param key A string used as the key for the data to be put in the store. The
|
||||
* key is later used to retrieve data from the store with Persistence_get().
|
||||
* @param bufcount The number of buffers to write to the persistence store.
|
||||
* @param buffers An array of pointers to the data buffers associated with
|
||||
* this <i>key</i>.
|
||||
* @param buflens An array of lengths of the data buffers. <i>buflen[n]</i>
|
||||
* gives the length of <i>buffer[n]</i>.
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_put)(void* handle, char* key, int bufcount, char* buffers[], int buflens[]);
|
||||
|
||||
/**
|
||||
* @brief Retrieve the specified data from the persistent store.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @param key A string that is the key for the data to be retrieved. This is
|
||||
* the same key used to save the data to the store with Persistence_put().
|
||||
* @param buffer The address of a pointer to a buffer. This function sets the
|
||||
* pointer to point at the retrieved data, if successful.
|
||||
* @param buflen The address of an int that is set to the length of
|
||||
* <i>buffer</i> by this function if successful.
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_get)(void* handle, char* key, char** buffer, int* buflen);
|
||||
|
||||
/**
|
||||
* @brief Remove the data for the specified key from the store.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @param key A string that is the key for the data to be removed from the
|
||||
* store. This is the same key used to save the data to the store with
|
||||
* Persistence_put().
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_remove)(void* handle, char* key);
|
||||
|
||||
/**
|
||||
* @brief Returns the keys in this persistent data store.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @param keys The address of a pointer to pointers to strings. Assuming
|
||||
* successful execution, this function allocates memory to hold the returned
|
||||
* keys (strings used to store the data with Persistence_put()). It also
|
||||
* allocates memory to hold an array of pointers to these strings. <i>keys</i>
|
||||
* is set to point to the array of pointers to strings.
|
||||
* @param nkeys A pointer to the number of keys in this persistent data store.
|
||||
* This function sets the number of keys, if successful.
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_keys)(void* handle, char*** keys, int* nkeys);
|
||||
|
||||
/**
|
||||
* @brief Clears the persistence store, so that it no longer contains any
|
||||
* persisted data.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @return Return 0 if the function completes successfully, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_clear)(void* handle);
|
||||
|
||||
/**
|
||||
* @brief Returns whether any data has been persisted using the specified key.
|
||||
*
|
||||
* @param handle The handle pointer from a successful call to
|
||||
* Persistence_open().
|
||||
* @param key The string to be tested for existence in the store.
|
||||
* @return Return 0 if the key was found in the store, otherwise return
|
||||
* ::MQTTCLIENT_PERSISTENCE_ERROR.
|
||||
*/
|
||||
typedef int (*Persistence_containskey)(void* handle, char* key);
|
||||
|
||||
/**
|
||||
* @brief A structure containing the function pointers to a persistence
|
||||
* implementation and the context or state that will be shared across all
|
||||
* the persistence functions.
|
||||
*/
|
||||
typedef struct {
|
||||
/**
|
||||
* A pointer to any data required to initialize the persistent store.
|
||||
*/
|
||||
void* context;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_open().
|
||||
*/
|
||||
Persistence_open popen;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_close().
|
||||
*/
|
||||
Persistence_close pclose;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_put().
|
||||
*/
|
||||
Persistence_put pput;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_get().
|
||||
*/
|
||||
Persistence_get pget;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_remove().
|
||||
*/
|
||||
Persistence_remove premove;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_keys().
|
||||
*/
|
||||
Persistence_keys pkeys;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_clear().
|
||||
*/
|
||||
Persistence_clear pclear;
|
||||
/**
|
||||
* A function pointer to an implementation of Persistence_containskey().
|
||||
*/
|
||||
Persistence_containskey pcontainskey;
|
||||
} MQTTClient_persistence;
|
||||
|
||||
#endif
|
||||
148
src/remote/include/paho_mqtt_3c/MQTTConnect.h
Normal file
148
src/remote/include/paho_mqtt_3c/MQTTConnect.h
Normal file
@ -0,0 +1,148 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2014, 2017 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - add connack return code definitions
|
||||
* Xiang Rong - 442039 Add makefile to Embedded C client
|
||||
* Ian Craggs - fix for issue #64, bit order in connack response
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef MQTTCONNECT_H_
|
||||
#define MQTTCONNECT_H_
|
||||
|
||||
enum connack_return_codes
|
||||
{
|
||||
MQTT_CONNECTION_ACCEPTED = 0,
|
||||
MQTT_UNNACCEPTABLE_PROTOCOL = 1,
|
||||
MQTT_CLIENTID_REJECTED = 2,
|
||||
MQTT_SERVER_UNAVAILABLE = 3,
|
||||
MQTT_BAD_USERNAME_OR_PASSWORD = 4,
|
||||
MQTT_NOT_AUTHORIZED = 5,
|
||||
};
|
||||
|
||||
#if !defined(DLLImport)
|
||||
#define DLLImport
|
||||
#endif
|
||||
#if !defined(DLLExport)
|
||||
#define DLLExport
|
||||
#endif
|
||||
|
||||
|
||||
typedef union
|
||||
{
|
||||
unsigned char all; /**< all connect flags */
|
||||
#if defined(REVERSED)
|
||||
struct
|
||||
{
|
||||
unsigned int username : 1; /**< 3.1 user name */
|
||||
unsigned int password : 1; /**< 3.1 password */
|
||||
unsigned int willRetain : 1; /**< will retain setting */
|
||||
unsigned int willQoS : 2; /**< will QoS value */
|
||||
unsigned int will : 1; /**< will flag */
|
||||
unsigned int cleansession : 1; /**< clean session flag */
|
||||
unsigned int : 1; /**< unused */
|
||||
} bits;
|
||||
#else
|
||||
struct
|
||||
{
|
||||
unsigned int : 1; /**< unused */
|
||||
unsigned int cleansession : 1; /**< cleansession flag */
|
||||
unsigned int will : 1; /**< will flag */
|
||||
unsigned int willQoS : 2; /**< will QoS value */
|
||||
unsigned int willRetain : 1; /**< will retain setting */
|
||||
unsigned int password : 1; /**< 3.1 password */
|
||||
unsigned int username : 1; /**< 3.1 user name */
|
||||
} bits;
|
||||
#endif
|
||||
} MQTTConnectFlags; /**< connect flags byte */
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Defines the MQTT "Last Will and Testament" (LWT) settings for
|
||||
* the connect packet.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** The eyecatcher for this structure. must be MQTW. */
|
||||
char struct_id[4];
|
||||
/** The version number of this structure. Must be 0 */
|
||||
int struct_version;
|
||||
/** The LWT topic to which the LWT message will be published. */
|
||||
MQTTString topicName;
|
||||
/** The LWT payload. */
|
||||
MQTTString message;
|
||||
/**
|
||||
* The retained flag for the LWT message (see MQTTAsync_message.retained).
|
||||
*/
|
||||
unsigned char retained;
|
||||
/**
|
||||
* The quality of service setting for the LWT message (see
|
||||
* MQTTAsync_message.qos and @ref qos).
|
||||
*/
|
||||
char qos;
|
||||
} MQTTPacket_willOptions;
|
||||
|
||||
|
||||
#define MQTTPacket_willOptions_initializer { {'M', 'Q', 'T', 'W'}, 0, {NULL, {0, NULL}}, {NULL, {0, NULL}}, 0, 0 }
|
||||
|
||||
|
||||
typedef struct
|
||||
{
|
||||
/** The eyecatcher for this structure. must be MQTC. */
|
||||
char struct_id[4];
|
||||
/** The version number of this structure. Must be 0 */
|
||||
int struct_version;
|
||||
/** Version of MQTT to be used. 3 = 3.1 4 = 3.1.1
|
||||
*/
|
||||
unsigned char MQTTVersion;
|
||||
MQTTString clientID;
|
||||
unsigned short keepAliveInterval;
|
||||
unsigned char cleansession;
|
||||
unsigned char willFlag;
|
||||
MQTTPacket_willOptions will;
|
||||
MQTTString username;
|
||||
MQTTString password;
|
||||
} MQTTPacket_connectData;
|
||||
|
||||
typedef union
|
||||
{
|
||||
unsigned char all; /**< all connack flags */
|
||||
#if defined(REVERSED)
|
||||
struct
|
||||
{
|
||||
unsigned int reserved : 7; /**< unused */
|
||||
unsigned int sessionpresent : 1; /**< session present flag */
|
||||
} bits;
|
||||
#else
|
||||
struct
|
||||
{
|
||||
unsigned int sessionpresent : 1; /**< session present flag */
|
||||
unsigned int reserved: 7; /**< unused */
|
||||
} bits;
|
||||
#endif
|
||||
} MQTTConnackFlags; /**< connack flags byte */
|
||||
|
||||
#define MQTTPacket_connectData_initializer { {'M', 'Q', 'T', 'C'}, 0, 4, {NULL, {0, NULL}}, 60, 1, 0, \
|
||||
MQTTPacket_willOptions_initializer, {NULL, {0, NULL}}, {NULL, {0, NULL}} }
|
||||
|
||||
DLLExport int MQTTSerialize_connect(unsigned char* buf, int buflen, MQTTPacket_connectData* options);
|
||||
DLLExport int MQTTDeserialize_connect(MQTTPacket_connectData* data, unsigned char* buf, int len);
|
||||
|
||||
DLLExport int MQTTSerialize_connack(unsigned char* buf, int buflen, unsigned char connack_rc, unsigned char sessionPresent);
|
||||
DLLExport int MQTTDeserialize_connack(unsigned char* sessionPresent, unsigned char* connack_rc, unsigned char* buf, int buflen);
|
||||
|
||||
DLLExport int MQTTSerialize_disconnect(unsigned char* buf, int buflen);
|
||||
DLLExport int MQTTSerialize_pingreq(unsigned char* buf, int buflen);
|
||||
|
||||
#endif /* MQTTCONNECT_H_ */
|
||||
37
src/remote/include/paho_mqtt_3c/MQTTFormat.h
Normal file
37
src/remote/include/paho_mqtt_3c/MQTTFormat.h
Normal file
@ -0,0 +1,37 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTFORMAT_H)
|
||||
#define MQTTFORMAT_H
|
||||
|
||||
#include "StackTrace.h"
|
||||
#include "MQTTPacket.h"
|
||||
|
||||
const char* MQTTPacket_getName(unsigned short packetid);
|
||||
int MQTTStringFormat_connect(char* strbuf, int strbuflen, MQTTPacket_connectData* data);
|
||||
int MQTTStringFormat_connack(char* strbuf, int strbuflen, unsigned char connack_rc, unsigned char sessionPresent);
|
||||
int MQTTStringFormat_publish(char* strbuf, int strbuflen, unsigned char dup, int qos, unsigned char retained,
|
||||
unsigned short packetid, MQTTString topicName, unsigned char* payload, int payloadlen);
|
||||
int MQTTStringFormat_ack(char* strbuf, int strbuflen, unsigned char packettype, unsigned char dup, unsigned short packetid);
|
||||
int MQTTStringFormat_subscribe(char* strbuf, int strbuflen, unsigned char dup, unsigned short packetid, int count,
|
||||
MQTTString topicFilters[], int requestedQoSs[]);
|
||||
int MQTTStringFormat_suback(char* strbuf, int strbuflen, unsigned short packetid, int count, int* grantedQoSs);
|
||||
int MQTTStringFormat_unsubscribe(char* strbuf, int strbuflen, unsigned char dup, unsigned short packetid,
|
||||
int count, MQTTString topicFilters[]);
|
||||
char* MQTTFormat_toClientString(char* strbuf, int strbuflen, unsigned char* buf, int buflen);
|
||||
char* MQTTFormat_toServerString(char* strbuf, int strbuflen, unsigned char* buf, int buflen);
|
||||
|
||||
#endif
|
||||
270
src/remote/include/paho_mqtt_3c/MQTTPacket.h
Normal file
270
src/remote/include/paho_mqtt_3c/MQTTPacket.h
Normal file
@ -0,0 +1,270 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs, Allan Stockdill-Mander - SSL updates
|
||||
* Ian Craggs - MQTT 3.1.1 support
|
||||
* Ian Craggs - big endian Linux reversed definition
|
||||
* Ian Craggs - MQTT 5.0 support
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPACKET_H)
|
||||
#define MQTTPACKET_H
|
||||
|
||||
#include "Socket.h"
|
||||
#if defined(OPENSSL)
|
||||
#include "SSLSocket.h"
|
||||
#endif
|
||||
#include "LinkedList.h"
|
||||
#include "Clients.h"
|
||||
|
||||
typedef unsigned int bool;
|
||||
typedef void* (*pf)(int, unsigned char, char*, size_t);
|
||||
|
||||
#include "MQTTProperties.h"
|
||||
#include "MQTTReasonCodes.h"
|
||||
|
||||
enum errors
|
||||
{
|
||||
MQTTPACKET_BAD = -4,
|
||||
MQTTPACKET_BUFFER_TOO_SHORT = -2,
|
||||
MQTTPACKET_READ_ERROR = -1,
|
||||
MQTTPACKET_READ_COMPLETE
|
||||
};
|
||||
|
||||
|
||||
enum msgTypes
|
||||
{
|
||||
CONNECT = 1, CONNACK, PUBLISH, PUBACK, PUBREC, PUBREL,
|
||||
PUBCOMP, SUBSCRIBE, SUBACK, UNSUBSCRIBE, UNSUBACK,
|
||||
PINGREQ, PINGRESP, DISCONNECT, AUTH
|
||||
};
|
||||
|
||||
#if defined(__linux__)
|
||||
#include <endian.h>
|
||||
#if __BYTE_ORDER == __BIG_ENDIAN
|
||||
#define REVERSED 1
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Bitfields for the MQTT header byte.
|
||||
*/
|
||||
typedef union
|
||||
{
|
||||
/*unsigned*/ char byte; /**< the whole byte */
|
||||
#if defined(REVERSED)
|
||||
struct
|
||||
{
|
||||
unsigned int type : 4; /**< message type nibble */
|
||||
bool dup : 1; /**< DUP flag bit */
|
||||
unsigned int qos : 2; /**< QoS value, 0, 1 or 2 */
|
||||
bool retain : 1; /**< retained flag bit */
|
||||
} bits;
|
||||
#else
|
||||
struct
|
||||
{
|
||||
bool retain : 1; /**< retained flag bit */
|
||||
unsigned int qos : 2; /**< QoS value, 0, 1 or 2 */
|
||||
bool dup : 1; /**< DUP flag bit */
|
||||
unsigned int type : 4; /**< message type nibble */
|
||||
} bits;
|
||||
#endif
|
||||
} Header;
|
||||
|
||||
|
||||
/**
|
||||
* Data for a connect packet.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
union
|
||||
{
|
||||
unsigned char all; /**< all connect flags */
|
||||
#if defined(REVERSED)
|
||||
struct
|
||||
{
|
||||
bool username : 1; /**< 3.1 user name */
|
||||
bool password : 1; /**< 3.1 password */
|
||||
bool willRetain : 1; /**< will retain setting */
|
||||
unsigned int willQoS : 2; /**< will QoS value */
|
||||
bool will : 1; /**< will flag */
|
||||
bool cleanstart : 1; /**< cleansession flag */
|
||||
int : 1; /**< unused */
|
||||
} bits;
|
||||
#else
|
||||
struct
|
||||
{
|
||||
int : 1; /**< unused */
|
||||
bool cleanstart : 1; /**< cleansession flag */
|
||||
bool will : 1; /**< will flag */
|
||||
unsigned int willQoS : 2; /**< will QoS value */
|
||||
bool willRetain : 1; /**< will retain setting */
|
||||
bool password : 1; /**< 3.1 password */
|
||||
bool username : 1; /**< 3.1 user name */
|
||||
} bits;
|
||||
#endif
|
||||
} flags; /**< connect flags byte */
|
||||
|
||||
char *Protocol, /**< MQTT protocol name */
|
||||
*clientID, /**< string client id */
|
||||
*willTopic, /**< will topic */
|
||||
*willMsg; /**< will payload */
|
||||
|
||||
int keepAliveTimer; /**< keepalive timeout value in seconds */
|
||||
unsigned char version; /**< MQTT version number */
|
||||
} Connect;
|
||||
|
||||
|
||||
/**
|
||||
* Data for a connack packet.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
union
|
||||
{
|
||||
unsigned char all; /**< all connack flags */
|
||||
#if defined(REVERSED)
|
||||
struct
|
||||
{
|
||||
unsigned int reserved : 7; /**< message type nibble */
|
||||
bool sessionPresent : 1; /**< was a session found on the server? */
|
||||
} bits;
|
||||
#else
|
||||
struct
|
||||
{
|
||||
bool sessionPresent : 1; /**< was a session found on the server? */
|
||||
unsigned int reserved : 7; /**< message type nibble */
|
||||
} bits;
|
||||
#endif
|
||||
} flags; /**< connack flags byte */
|
||||
unsigned char rc; /**< connack reason code */
|
||||
unsigned int MQTTVersion; /**< the version of MQTT */
|
||||
MQTTProperties properties; /**< MQTT 5.0 properties. Not used for MQTT < 5.0 */
|
||||
} Connack;
|
||||
|
||||
|
||||
/**
|
||||
* Data for a packet with header only.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
} MQTTPacket;
|
||||
|
||||
|
||||
/**
|
||||
* Data for a suback packet.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
int msgId; /**< MQTT message id */
|
||||
int MQTTVersion; /**< the version of MQTT */
|
||||
MQTTProperties properties; /**< MQTT 5.0 properties. Not used for MQTT < 5.0 */
|
||||
List* qoss; /**< list of granted QoSs (MQTT 3/4) / reason codes (MQTT 5) */
|
||||
} Suback;
|
||||
|
||||
|
||||
/**
|
||||
* Data for an MQTT V5 unsuback packet.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
int msgId; /**< MQTT message id */
|
||||
int MQTTVersion; /**< the version of MQTT */
|
||||
MQTTProperties properties; /**< MQTT 5.0 properties. Not used for MQTT < 5.0 */
|
||||
List* reasonCodes; /**< list of reason codes */
|
||||
} Unsuback;
|
||||
|
||||
|
||||
/**
|
||||
* Data for a publish packet.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
char* topic; /**< topic string */
|
||||
int topiclen;
|
||||
int msgId; /**< MQTT message id */
|
||||
char* payload; /**< binary payload, length delimited */
|
||||
int payloadlen; /**< payload length */
|
||||
int MQTTVersion; /**< the version of MQTT */
|
||||
MQTTProperties properties; /**< MQTT 5.0 properties. Not used for MQTT < 5.0 */
|
||||
} Publish;
|
||||
|
||||
|
||||
/**
|
||||
* Data for one of the ack packets.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
Header header; /**< MQTT header byte */
|
||||
int msgId; /**< MQTT message id */
|
||||
unsigned char rc; /**< MQTT 5 reason code */
|
||||
int MQTTVersion; /**< the version of MQTT */
|
||||
MQTTProperties properties; /**< MQTT 5.0 properties. Not used for MQTT < 5.0 */
|
||||
} Ack;
|
||||
|
||||
typedef Ack Puback;
|
||||
typedef Ack Pubrec;
|
||||
typedef Ack Pubrel;
|
||||
typedef Ack Pubcomp;
|
||||
|
||||
int MQTTPacket_encode(char* buf, size_t length);
|
||||
int MQTTPacket_decode(networkHandles* net, size_t* value);
|
||||
int readInt(char** pptr);
|
||||
char* readUTF(char** pptr, char* enddata);
|
||||
unsigned char readChar(char** pptr);
|
||||
void writeChar(char** pptr, char c);
|
||||
void writeInt(char** pptr, int anInt);
|
||||
void writeUTF(char** pptr, const char* string);
|
||||
void writeData(char** pptr, const void* data, int datalen);
|
||||
|
||||
const char* MQTTPacket_name(int ptype);
|
||||
|
||||
void* MQTTPacket_Factory(int MQTTVersion, networkHandles* net, int* error);
|
||||
int MQTTPacket_send(networkHandles* net, Header header, char* buffer, size_t buflen, int free, int MQTTVersion);
|
||||
int MQTTPacket_sends(networkHandles* net, Header header, int count, char** buffers, size_t* buflens, int* frees, int MQTTVersion);
|
||||
|
||||
void* MQTTPacket_header_only(int MQTTVersion, unsigned char aHeader, char* data, size_t datalen);
|
||||
int MQTTPacket_send_disconnect(Clients* client, enum MQTTReasonCodes reason, MQTTProperties* props);
|
||||
|
||||
void* MQTTPacket_publish(int MQTTVersion, unsigned char aHeader, char* data, size_t datalen);
|
||||
void MQTTPacket_freePublish(Publish* pack);
|
||||
int MQTTPacket_send_publish(Publish* pack, int dup, int qos, int retained, networkHandles* net, const char* clientID);
|
||||
int MQTTPacket_send_puback(int msgid, networkHandles* net, const char* clientID);
|
||||
void* MQTTPacket_ack(int MQTTVersion, unsigned char aHeader, char* data, size_t datalen);
|
||||
|
||||
void MQTTPacket_freeAck(Ack* pack);
|
||||
void MQTTPacket_freeSuback(Suback* pack);
|
||||
void MQTTPacket_freeUnsuback(Unsuback* pack);
|
||||
int MQTTPacket_send_pubrec(int msgid, networkHandles* net, const char* clientID);
|
||||
int MQTTPacket_send_pubrel(int msgid, int dup, networkHandles* net, const char* clientID);
|
||||
int MQTTPacket_send_pubcomp(int msgid, networkHandles* net, const char* clientID);
|
||||
|
||||
void MQTTPacket_free_packet(MQTTPacket* pack);
|
||||
|
||||
void writeInt4(char** pptr, int anInt);
|
||||
int readInt4(char** pptr);
|
||||
void writeMQTTLenString(char** pptr, MQTTLenString lenstring);
|
||||
int MQTTLenStringRead(MQTTLenString* lenstring, char** pptr, char* enddata);
|
||||
int MQTTPacket_VBIlen(int rem_len);
|
||||
int MQTTPacket_decodeBuf(char* buf, int* value);
|
||||
|
||||
#include "MQTTPacketOut.h"
|
||||
|
||||
#endif /* MQTTPACKET_H */
|
||||
39
src/remote/include/paho_mqtt_3c/MQTTPacketOut.h
Normal file
39
src/remote/include/paho_mqtt_3c/MQTTPacketOut.h
Normal file
@ -0,0 +1,39 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs, Allan Stockdill-Mander - SSL updates
|
||||
* Ian Craggs - MQTT 3.1.1 support
|
||||
* Ian Craggs - MQTT 5.0 support
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPACKETOUT_H)
|
||||
#define MQTTPACKETOUT_H
|
||||
|
||||
#include "MQTTPacket.h"
|
||||
|
||||
int MQTTPacket_send_connect(Clients* client, int MQTTVersion,
|
||||
MQTTProperties* connectProperties, MQTTProperties* willProperties);
|
||||
void* MQTTPacket_connack(int MQTTVersion, unsigned char aHeader, char* data, size_t datalen);
|
||||
void MQTTPacket_freeConnack(Connack* pack);
|
||||
|
||||
int MQTTPacket_send_pingreq(networkHandles* net, const char* clientID);
|
||||
|
||||
int MQTTPacket_send_subscribe(List* topics, List* qoss, MQTTSubscribe_options* opts, MQTTProperties* props,
|
||||
int msgid, int dup, Clients* client);
|
||||
void* MQTTPacket_suback(int MQTTVersion, unsigned char aHeader, char* data, size_t datalen);
|
||||
|
||||
int MQTTPacket_send_unsubscribe(List* topics, MQTTProperties* props, int msgid, int dup, Clients* client);
|
||||
void* MQTTPacket_unsuback(int MQTTVersion, unsigned char aHeader, char* data, size_t datalen);
|
||||
|
||||
#endif
|
||||
94
src/remote/include/paho_mqtt_3c/MQTTPersistence.h
Normal file
94
src/remote/include/paho_mqtt_3c/MQTTPersistence.h
Normal file
@ -0,0 +1,94 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - async client updates
|
||||
* Ian Craggs - fix for bug 432903 - queue persistence
|
||||
* Ian Craggs - MQTT V5 updates
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPERSISTENCE_H)
|
||||
#define MQTTPERSISTENCE_H
|
||||
|
||||
#if defined(__cplusplus)
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include "Clients.h"
|
||||
#include "MQTTProperties.h"
|
||||
|
||||
/** Stem of the key for a sent PUBLISH QoS1 or QoS2 */
|
||||
#define PERSISTENCE_PUBLISH_SENT "s-"
|
||||
/** Stem of the key for a sent PUBREL */
|
||||
#define PERSISTENCE_PUBREL "sc-"
|
||||
/** Stem of the key for a received PUBLISH QoS2 */
|
||||
#define PERSISTENCE_PUBLISH_RECEIVED "r-"
|
||||
|
||||
/** Stem of the key for a sent MQTT V5 PUBLISH QoS1 or QoS2 */
|
||||
#define PERSISTENCE_V5_PUBLISH_SENT "s5-"
|
||||
/** Stem of the key for a sent MQTT V5 PUBREL */
|
||||
#define PERSISTENCE_V5_PUBREL "sc5-"
|
||||
/** Stem of the key for a received MQTT V5 PUBLISH QoS2 */
|
||||
#define PERSISTENCE_V5_PUBLISH_RECEIVED "r5-"
|
||||
|
||||
/** Stem of the key for an async client command */
|
||||
#define PERSISTENCE_COMMAND_KEY "c-"
|
||||
/** Stem of the key for an MQTT V5 async client command */
|
||||
#define PERSISTENCE_V5_COMMAND_KEY "c-"
|
||||
/** Stem of the key for an async client message queue */
|
||||
#define PERSISTENCE_QUEUE_KEY "q-"
|
||||
/** Stem of the key for an MQTT V5 message queue */
|
||||
#define PERSISTENCE_V5_QUEUE_KEY "q5-"
|
||||
#define PERSISTENCE_MAX_KEY_LENGTH 8
|
||||
|
||||
int MQTTPersistence_create(MQTTClient_persistence** per, int type, void* pcontext);
|
||||
int MQTTPersistence_initialize(Clients* c, const char* serverURI);
|
||||
int MQTTPersistence_close(Clients* c);
|
||||
int MQTTPersistence_clear(Clients* c);
|
||||
int MQTTPersistence_restore(Clients* c);
|
||||
void* MQTTPersistence_restorePacket(int MQTTVersion, char* buffer, size_t buflen);
|
||||
void MQTTPersistence_insertInOrder(List* list, void* content, size_t size);
|
||||
int MQTTPersistence_put(int socket, char* buf0, size_t buf0len, int count,
|
||||
char** buffers, size_t* buflens, int htype, int msgId, int scr, int MQTTVersion);
|
||||
int MQTTPersistence_remove(Clients* c, char* type, int qos, int msgId);
|
||||
void MQTTPersistence_wrapMsgID(Clients *c);
|
||||
|
||||
typedef struct
|
||||
{
|
||||
char struct_id[4];
|
||||
int struct_version;
|
||||
int payloadlen;
|
||||
void* payload;
|
||||
int qos;
|
||||
int retained;
|
||||
int dup;
|
||||
int msgid;
|
||||
MQTTProperties properties;
|
||||
} MQTTPersistence_message;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
MQTTPersistence_message* msg;
|
||||
char* topicName;
|
||||
int topicLen;
|
||||
unsigned int seqno; /* only used on restore */
|
||||
} MQTTPersistence_qEntry;
|
||||
|
||||
int MQTTPersistence_unpersistQueueEntry(Clients* client, MQTTPersistence_qEntry* qe);
|
||||
int MQTTPersistence_persistQueueEntry(Clients* aclient, MQTTPersistence_qEntry* qe);
|
||||
int MQTTPersistence_restoreMessageQueue(Clients* c);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
38
src/remote/include/paho_mqtt_3c/MQTTPersistenceDefault.h
Normal file
38
src/remote/include/paho_mqtt_3c/MQTTPersistenceDefault.h
Normal file
@ -0,0 +1,38 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPERSISTENCEDEFAULT_H)
|
||||
#define MQTTPERSISTENCEDEFAULT_H
|
||||
|
||||
/** 8.3 filesystem */
|
||||
#define MESSAGE_FILENAME_LENGTH 8
|
||||
/** Extension of the filename */
|
||||
#define MESSAGE_FILENAME_EXTENSION ".msg"
|
||||
|
||||
/* prototypes of the functions for the default file system persistence */
|
||||
int pstopen(void** handle, const char* clientID, const char* serverURI, void* context);
|
||||
int pstclose(void* handle);
|
||||
int pstput(void* handle, char* key, int bufcount, char* buffers[], int buflens[]);
|
||||
int pstget(void* handle, char* key, char** buffer, int* buflen);
|
||||
int pstremove(void* handle, char* key);
|
||||
int pstkeys(void* handle, char*** keys, int* nkeys);
|
||||
int pstclear(void* handle);
|
||||
int pstcontainskey(void* handle, char* key);
|
||||
|
||||
int pstmkdir(char *pPathname);
|
||||
|
||||
#endif
|
||||
|
||||
225
src/remote/include/paho_mqtt_3c/MQTTProperties.h
Normal file
225
src/remote/include/paho_mqtt_3c/MQTTProperties.h
Normal file
@ -0,0 +1,225 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2017, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPROPERTIES_H)
|
||||
#define MQTTPROPERTIES_H
|
||||
|
||||
#define MQTT_INVALID_PROPERTY_ID -2
|
||||
|
||||
/** The one byte MQTT V5 property indicator */
|
||||
enum MQTTPropertyCodes {
|
||||
MQTTPROPERTY_CODE_PAYLOAD_FORMAT_INDICATOR = 1, /**< The value is 1 */
|
||||
MQTTPROPERTY_CODE_MESSAGE_EXPIRY_INTERVAL = 2, /**< The value is 2 */
|
||||
MQTTPROPERTY_CODE_CONTENT_TYPE = 3, /**< The value is 3 */
|
||||
MQTTPROPERTY_CODE_RESPONSE_TOPIC = 8, /**< The value is 8 */
|
||||
MQTTPROPERTY_CODE_CORRELATION_DATA = 9, /**< The value is 9 */
|
||||
MQTTPROPERTY_CODE_SUBSCRIPTION_IDENTIFIER = 11, /**< The value is 11 */
|
||||
MQTTPROPERTY_CODE_SESSION_EXPIRY_INTERVAL = 17, /**< The value is 17 */
|
||||
MQTTPROPERTY_CODE_ASSIGNED_CLIENT_IDENTIFER = 18,/**< The value is 18 */
|
||||
MQTTPROPERTY_CODE_SERVER_KEEP_ALIVE = 19, /**< The value is 19 */
|
||||
MQTTPROPERTY_CODE_AUTHENTICATION_METHOD = 21, /**< The value is 21 */
|
||||
MQTTPROPERTY_CODE_AUTHENTICATION_DATA = 22, /**< The value is 22 */
|
||||
MQTTPROPERTY_CODE_REQUEST_PROBLEM_INFORMATION = 23,/**< The value is 23 */
|
||||
MQTTPROPERTY_CODE_WILL_DELAY_INTERVAL = 24, /**< The value is 24 */
|
||||
MQTTPROPERTY_CODE_REQUEST_RESPONSE_INFORMATION = 25,/**< The value is 25 */
|
||||
MQTTPROPERTY_CODE_RESPONSE_INFORMATION = 26, /**< The value is 26 */
|
||||
MQTTPROPERTY_CODE_SERVER_REFERENCE = 28, /**< The value is 28 */
|
||||
MQTTPROPERTY_CODE_REASON_STRING = 31, /**< The value is 31 */
|
||||
MQTTPROPERTY_CODE_RECEIVE_MAXIMUM = 33, /**< The value is 33*/
|
||||
MQTTPROPERTY_CODE_TOPIC_ALIAS_MAXIMUM = 34, /**< The value is 34 */
|
||||
MQTTPROPERTY_CODE_TOPIC_ALIAS = 35, /**< The value is 35 */
|
||||
MQTTPROPERTY_CODE_MAXIMUM_QOS = 36, /**< The value is 36 */
|
||||
MQTTPROPERTY_CODE_RETAIN_AVAILABLE = 37, /**< The value is 37 */
|
||||
MQTTPROPERTY_CODE_USER_PROPERTY = 38, /**< The value is 38 */
|
||||
MQTTPROPERTY_CODE_MAXIMUM_PACKET_SIZE = 39, /**< The value is 39 */
|
||||
MQTTPROPERTY_CODE_WILDCARD_SUBSCRIPTION_AVAILABLE = 40,/**< The value is 40 */
|
||||
MQTTPROPERTY_CODE_SUBSCRIPTION_IDENTIFIERS_AVAILABLE = 41,/**< The value is 41 */
|
||||
MQTTPROPERTY_CODE_SHARED_SUBSCRIPTION_AVAILABLE = 42/**< The value is 241 */
|
||||
};
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#define DLLImport __declspec(dllimport)
|
||||
#define DLLExport __declspec(dllexport)
|
||||
#else
|
||||
#define DLLImport extern
|
||||
#define DLLExport __attribute__ ((visibility ("default")))
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Returns a printable string description of an MQTT V5 property code.
|
||||
* @param value an MQTT V5 property code.
|
||||
* @return the printable string description of the input property code.
|
||||
* NULL if the code was not found.
|
||||
*/
|
||||
DLLExport const char* MQTTPropertyName(enum MQTTPropertyCodes value);
|
||||
|
||||
/** The one byte MQTT V5 property type */
|
||||
enum MQTTPropertyTypes {
|
||||
MQTTPROPERTY_TYPE_BYTE,
|
||||
MQTTPROPERTY_TYPE_TWO_BYTE_INTEGER,
|
||||
MQTTPROPERTY_TYPE_FOUR_BYTE_INTEGER,
|
||||
MQTTPROPERTY_TYPE_VARIABLE_BYTE_INTEGER,
|
||||
MQTTPROPERTY_TYPE_BINARY_DATA,
|
||||
MQTTPROPERTY_TYPE_UTF_8_ENCODED_STRING,
|
||||
MQTTPROPERTY_TYPE_UTF_8_STRING_PAIR
|
||||
};
|
||||
|
||||
/**
|
||||
* Returns the MQTT V5 type code of an MQTT V5 property.
|
||||
* @param value an MQTT V5 property code.
|
||||
* @return the MQTT V5 type code of the input property. -1 if the code was not found.
|
||||
*/
|
||||
DLLExport int MQTTProperty_getType(enum MQTTPropertyCodes value);
|
||||
|
||||
/**
|
||||
* The data for a length delimited string
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
int len; /**< the length of the string */
|
||||
char* data; /**< pointer to the string data */
|
||||
} MQTTLenString;
|
||||
|
||||
|
||||
/**
|
||||
* Structure to hold an MQTT version 5 property of any type
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
enum MQTTPropertyCodes identifier; /**< The MQTT V5 property id. A multi-byte integer. */
|
||||
/** The value of the property, as a union of the different possible types. */
|
||||
union {
|
||||
char byte; /**< holds the value of a byte property type */
|
||||
short integer2; /**< holds the value of a 2 byte integer property type */
|
||||
int integer4; /**< holds the value of a 4 byte integer property type */
|
||||
struct {
|
||||
MQTTLenString data; /**< The value of a string property, or the name of a user property. */
|
||||
MQTTLenString value; /**< The value of a user property. */
|
||||
};
|
||||
} value;
|
||||
} MQTTProperty;
|
||||
|
||||
/**
|
||||
* MQTT version 5 property list
|
||||
*/
|
||||
typedef struct MQTTProperties
|
||||
{
|
||||
int count; /**< number of property entries in the array */
|
||||
int max_count; /**< max number of properties that the currently allocated array can store */
|
||||
int length; /**< mbi: byte length of all properties */
|
||||
MQTTProperty *array; /**< array of properties */
|
||||
} MQTTProperties;
|
||||
|
||||
#define MQTTProperties_initializer {0, 0, 0, NULL}
|
||||
|
||||
/**
|
||||
* Returns the length of the properties structure when serialized ready for network transmission.
|
||||
* @param props an MQTT V5 property structure.
|
||||
* @return the length in bytes of the properties when serialized.
|
||||
*/
|
||||
int MQTTProperties_len(MQTTProperties* props);
|
||||
|
||||
/**
|
||||
* Add a property pointer to the property array. There is no memory allocation.
|
||||
* @param props The property list to add the property to.
|
||||
* @param prop The property to add to the list.
|
||||
* @return 0 on success, -1 on failure.
|
||||
*/
|
||||
DLLExport int MQTTProperties_add(MQTTProperties* props, const MQTTProperty* prop);
|
||||
|
||||
/**
|
||||
* Serialize the given property list to a character buffer, e.g. for writing to the network.
|
||||
* @param pptr pointer to the buffer - move the pointer as we add data
|
||||
* @param properties pointer to the property list, can be NULL
|
||||
* @return whether the write succeeded or not: number of bytes written, or < 0 on failure.
|
||||
*/
|
||||
int MQTTProperties_write(char** pptr, const MQTTProperties* properties);
|
||||
|
||||
/**
|
||||
* Reads a property list from a character buffer into an array.
|
||||
* @param properties pointer to the property list to be filled. Should be initalized but empty.
|
||||
* @param pptr pointer to the character buffer.
|
||||
* @param enddata pointer to the end of the character buffer so we don't read beyond.
|
||||
* @return 1 if the properties were read successfully.
|
||||
*/
|
||||
int MQTTProperties_read(MQTTProperties* properties, char** pptr, char* enddata);
|
||||
|
||||
/**
|
||||
* Free all memory allocated to the property list, including any to individual properties.
|
||||
* @param properties pointer to the property list.
|
||||
*/
|
||||
DLLExport void MQTTProperties_free(MQTTProperties* properties);
|
||||
|
||||
/**
|
||||
* Copy the contents of a property list, allocating additional memory if needed.
|
||||
* @param props pointer to the property list.
|
||||
* @return the duplicated property list.
|
||||
*/
|
||||
DLLExport MQTTProperties MQTTProperties_copy(const MQTTProperties* props);
|
||||
|
||||
/**
|
||||
* Checks if property list contains a specific property.
|
||||
* @param props pointer to the property list.
|
||||
* @param propid the property id to check for.
|
||||
* @return 1 if found, 0 if not.
|
||||
*/
|
||||
DLLExport int MQTTProperties_hasProperty(MQTTProperties *props, enum MQTTPropertyCodes propid);
|
||||
|
||||
/**
|
||||
* Returns the number of instances of a property id. Most properties can exist only once.
|
||||
* User properties and subscription ids can exist more than once.
|
||||
* @param props pointer to the property list.
|
||||
* @param propid the property id to check for.
|
||||
* @return the number of times found. Can be 0.
|
||||
*/
|
||||
DLLExport int MQTTProperties_propertyCount(MQTTProperties *props, enum MQTTPropertyCodes propid);
|
||||
|
||||
/**
|
||||
* Returns the integer value of a specific property. The property given must be a numeric type.
|
||||
* @param props pointer to the property list.
|
||||
* @param propid the property id to check for.
|
||||
* @return the integer value of the property. -9999999 on failure.
|
||||
*/
|
||||
DLLExport int MQTTProperties_getNumericValue(MQTTProperties *props, enum MQTTPropertyCodes propid);
|
||||
|
||||
/**
|
||||
* Returns the integer value of a specific property when it's not the only instance.
|
||||
* The property given must be a numeric type.
|
||||
* @param props pointer to the property list.
|
||||
* @param propid the property id to check for.
|
||||
* @param index the instance number, starting at 0.
|
||||
* @return the integer value of the property. -9999999 on failure.
|
||||
*/
|
||||
DLLExport int MQTTProperties_getNumericValueAt(MQTTProperties *props, enum MQTTPropertyCodes propid, int index);
|
||||
|
||||
/**
|
||||
* Returns a pointer to the property structure for a specific property.
|
||||
* @param props pointer to the property list.
|
||||
* @param propid the property id to check for.
|
||||
* @return the pointer to the property structure if found. NULL if not found.
|
||||
*/
|
||||
DLLExport MQTTProperty* MQTTProperties_getProperty(MQTTProperties *props, enum MQTTPropertyCodes propid);
|
||||
|
||||
/**
|
||||
* Returns a pointer to the property structure for a specific property when it's not the only instance.
|
||||
* @param props pointer to the property list.
|
||||
* @param propid the property id to check for.
|
||||
* @param index the instance number, starting at 0.
|
||||
* @return the pointer to the property structure if found. NULL if not found.
|
||||
*/
|
||||
DLLExport MQTTProperty* MQTTProperties_getPropertyAt(MQTTProperties *props, enum MQTTPropertyCodes propid, int index);
|
||||
|
||||
#endif /* MQTTPROPERTIES_H */
|
||||
46
src/remote/include/paho_mqtt_3c/MQTTProtocol.h
Normal file
46
src/remote/include/paho_mqtt_3c/MQTTProtocol.h
Normal file
@ -0,0 +1,46 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs - MQTT 3.1.1 updates
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPROTOCOL_H)
|
||||
#define MQTTPROTOCOL_H
|
||||
|
||||
#include "LinkedList.h"
|
||||
#include "MQTTPacket.h"
|
||||
#include "Clients.h"
|
||||
|
||||
#define MAX_MSG_ID 65535
|
||||
#define MAX_CLIENTID_LEN 65535
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int socket;
|
||||
Publications* p;
|
||||
} pending_write;
|
||||
|
||||
|
||||
typedef struct
|
||||
{
|
||||
List publications;
|
||||
unsigned int msgs_received;
|
||||
unsigned int msgs_sent;
|
||||
List pending_writes; /* for qos 0 writes not complete */
|
||||
} MQTTProtocol;
|
||||
|
||||
|
||||
#include "MQTTProtocolOut.h"
|
||||
|
||||
#endif
|
||||
60
src/remote/include/paho_mqtt_3c/MQTTProtocolClient.h
Normal file
60
src/remote/include/paho_mqtt_3c/MQTTProtocolClient.h
Normal file
@ -0,0 +1,60 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2017 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs, Allan Stockdill-Mander - SSL updates
|
||||
* Ian Craggs - MQTT 3.1.1 updates
|
||||
* Rong Xiang, Ian Craggs - C++ compatibility
|
||||
* Ian Craggs - add debug definition of MQTTStrdup for when needed
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPROTOCOLCLIENT_H)
|
||||
#define MQTTPROTOCOLCLIENT_H
|
||||
|
||||
#include "LinkedList.h"
|
||||
#include "MQTTPacket.h"
|
||||
#include "Log.h"
|
||||
#include "MQTTProtocol.h"
|
||||
#include "Messages.h"
|
||||
#include "MQTTProperties.h"
|
||||
|
||||
#define MAX_MSG_ID 65535
|
||||
#define MAX_CLIENTID_LEN 65535
|
||||
|
||||
int MQTTProtocol_startPublish(Clients* pubclient, Publish* publish, int qos, int retained, Messages** m);
|
||||
Messages* MQTTProtocol_createMessage(Publish* publish, Messages** mm, int qos, int retained);
|
||||
Publications* MQTTProtocol_storePublication(Publish* publish, int* len);
|
||||
int messageIDCompare(void* a, void* b);
|
||||
int MQTTProtocol_assignMsgId(Clients* client);
|
||||
void MQTTProtocol_removePublication(Publications* p);
|
||||
void Protocol_processPublication(Publish* publish, Clients* client);
|
||||
|
||||
int MQTTProtocol_handlePublishes(void* pack, int sock);
|
||||
int MQTTProtocol_handlePubacks(void* pack, int sock);
|
||||
int MQTTProtocol_handlePubrecs(void* pack, int sock);
|
||||
int MQTTProtocol_handlePubrels(void* pack, int sock);
|
||||
int MQTTProtocol_handlePubcomps(void* pack, int sock);
|
||||
|
||||
void MQTTProtocol_closeSession(Clients* c, int sendwill);
|
||||
void MQTTProtocol_keepalive(time_t);
|
||||
void MQTTProtocol_retry(time_t, int, int);
|
||||
void MQTTProtocol_freeClient(Clients* client);
|
||||
void MQTTProtocol_emptyMessageList(List* msgList);
|
||||
void MQTTProtocol_freeMessageList(List* msgList);
|
||||
|
||||
char* MQTTStrncpy(char *dest, const char* src, size_t num);
|
||||
char* MQTTStrdup(const char* src);
|
||||
|
||||
//#define MQTTStrdup(src) MQTTStrncpy(malloc(strlen(src)+1), src, strlen(src)+1)
|
||||
|
||||
#endif
|
||||
50
src/remote/include/paho_mqtt_3c/MQTTProtocolOut.h
Normal file
50
src/remote/include/paho_mqtt_3c/MQTTProtocolOut.h
Normal file
@ -0,0 +1,50 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs, Allan Stockdill-Mander - SSL updates
|
||||
* Ian Craggs - MQTT 3.1.1 support
|
||||
* Ian Craggs - SNI support
|
||||
* Ian Craggs - MQTT 5.0 support
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTPROTOCOLOUT_H)
|
||||
#define MQTTPROTOCOLOUT_H
|
||||
|
||||
#include "LinkedList.h"
|
||||
#include "MQTTPacket.h"
|
||||
#include "Clients.h"
|
||||
#include "Log.h"
|
||||
#include "Messages.h"
|
||||
#include "MQTTProtocol.h"
|
||||
#include "MQTTProtocolClient.h"
|
||||
|
||||
#define DEFAULT_PORT 1883
|
||||
|
||||
size_t MQTTProtocol_addressPort(const char* uri, int* port, const char **topic);
|
||||
void MQTTProtocol_reconnect(const char* ip_address, Clients* client);
|
||||
#if defined(OPENSSL)
|
||||
int MQTTProtocol_connect(const char* ip_address, Clients* acClients, int ssl, int websocket, int MQTTVersion,
|
||||
MQTTProperties* connectProperties, MQTTProperties* willProperties);
|
||||
#else
|
||||
int MQTTProtocol_connect(const char* ip_address, Clients* acClients, int websocket, int MQTTVersion,
|
||||
MQTTProperties* connectProperties, MQTTProperties* willProperties);
|
||||
#endif
|
||||
int MQTTProtocol_handlePingresps(void* pack, int sock);
|
||||
int MQTTProtocol_subscribe(Clients* client, List* topics, List* qoss, int msgID,
|
||||
MQTTSubscribe_options* opts, MQTTProperties* props);
|
||||
int MQTTProtocol_handleSubacks(void* pack, int sock);
|
||||
int MQTTProtocol_unsubscribe(Clients* client, List* topics, int msgID, MQTTProperties* props);
|
||||
int MQTTProtocol_handleUnsubacks(void* pack, int sock);
|
||||
|
||||
#endif
|
||||
38
src/remote/include/paho_mqtt_3c/MQTTPublish.h
Normal file
38
src/remote/include/paho_mqtt_3c/MQTTPublish.h
Normal file
@ -0,0 +1,38 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Xiang Rong - 442039 Add makefile to Embedded C client
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef MQTTPUBLISH_H_
|
||||
#define MQTTPUBLISH_H_
|
||||
|
||||
#if !defined(DLLImport)
|
||||
#define DLLImport
|
||||
#endif
|
||||
#if !defined(DLLExport)
|
||||
#define DLLExport
|
||||
#endif
|
||||
|
||||
DLLExport int MQTTSerialize_publish(unsigned char* buf, int buflen, unsigned char dup, int qos, unsigned char retained, unsigned short packetid,
|
||||
MQTTString topicName, unsigned char* payload, int payloadlen);
|
||||
|
||||
DLLExport int MQTTDeserialize_publish(unsigned char* dup, int* qos, unsigned char* retained, unsigned short* packetid, MQTTString* topicName,
|
||||
unsigned char** payload, int* payloadlen, unsigned char* buf, int len);
|
||||
|
||||
DLLExport int MQTTSerialize_puback(unsigned char* buf, int buflen, unsigned short packetid);
|
||||
DLLExport int MQTTSerialize_pubrel(unsigned char* buf, int buflen, unsigned char dup, unsigned short packetid);
|
||||
DLLExport int MQTTSerialize_pubcomp(unsigned char* buf, int buflen, unsigned short packetid);
|
||||
|
||||
#endif /* MQTTPUBLISH_H_ */
|
||||
85
src/remote/include/paho_mqtt_3c/MQTTReasonCodes.h
Normal file
85
src/remote/include/paho_mqtt_3c/MQTTReasonCodes.h
Normal file
@ -0,0 +1,85 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2017, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MQTTREASONCODES_H)
|
||||
#define MQTTREASONCODES_H
|
||||
|
||||
/** The MQTT V5 one byte reason code */
|
||||
enum MQTTReasonCodes {
|
||||
MQTTREASONCODE_SUCCESS = 0,
|
||||
MQTTREASONCODE_NORMAL_DISCONNECTION = 0,
|
||||
MQTTREASONCODE_GRANTED_QOS_0 = 0,
|
||||
MQTTREASONCODE_GRANTED_QOS_1 = 1,
|
||||
MQTTREASONCODE_GRANTED_QOS_2 = 2,
|
||||
MQTTREASONCODE_DISCONNECT_WITH_WILL_MESSAGE = 4,
|
||||
MQTTREASONCODE_NO_MATCHING_SUBSCRIBERS = 16,
|
||||
MQTTREASONCODE_NO_SUBSCRIPTION_FOUND = 17,
|
||||
MQTTREASONCODE_CONTINUE_AUTHENTICATION = 24,
|
||||
MQTTREASONCODE_RE_AUTHENTICATE = 25,
|
||||
MQTTREASONCODE_UNSPECIFIED_ERROR = 128,
|
||||
MQTTREASONCODE_MALFORMED_PACKET = 129,
|
||||
MQTTREASONCODE_PROTOCOL_ERROR = 130,
|
||||
MQTTREASONCODE_IMPLEMENTATION_SPECIFIC_ERROR = 131,
|
||||
MQTTREASONCODE_UNSUPPORTED_PROTOCOL_VERSION = 132,
|
||||
MQTTREASONCODE_CLIENT_IDENTIFIER_NOT_VALID = 133,
|
||||
MQTTREASONCODE_BAD_USER_NAME_OR_PASSWORD = 134,
|
||||
MQTTREASONCODE_NOT_AUTHORIZED = 135,
|
||||
MQTTREASONCODE_SERVER_UNAVAILABLE = 136,
|
||||
MQTTREASONCODE_SERVER_BUSY = 137,
|
||||
MQTTREASONCODE_BANNED = 138,
|
||||
MQTTREASONCODE_SERVER_SHUTTING_DOWN = 139,
|
||||
MQTTREASONCODE_BAD_AUTHENTICATION_METHOD = 140,
|
||||
MQTTREASONCODE_KEEP_ALIVE_TIMEOUT = 141,
|
||||
MQTTREASONCODE_SESSION_TAKEN_OVER = 142,
|
||||
MQTTREASONCODE_TOPIC_FILTER_INVALID = 143,
|
||||
MQTTREASONCODE_TOPIC_NAME_INVALID = 144,
|
||||
MQTTREASONCODE_PACKET_IDENTIFIER_IN_USE = 145,
|
||||
MQTTREASONCODE_PACKET_IDENTIFIER_NOT_FOUND = 146,
|
||||
MQTTREASONCODE_RECEIVE_MAXIMUM_EXCEEDED = 147,
|
||||
MQTTREASONCODE_TOPIC_ALIAS_INVALID = 148,
|
||||
MQTTREASONCODE_PACKET_TOO_LARGE = 149,
|
||||
MQTTREASONCODE_MESSAGE_RATE_TOO_HIGH = 150,
|
||||
MQTTREASONCODE_QUOTA_EXCEEDED = 151,
|
||||
MQTTREASONCODE_ADMINISTRATIVE_ACTION = 152,
|
||||
MQTTREASONCODE_PAYLOAD_FORMAT_INVALID = 153,
|
||||
MQTTREASONCODE_RETAIN_NOT_SUPPORTED = 154,
|
||||
MQTTREASONCODE_QOS_NOT_SUPPORTED = 155,
|
||||
MQTTREASONCODE_USE_ANOTHER_SERVER = 156,
|
||||
MQTTREASONCODE_SERVER_MOVED = 157,
|
||||
MQTTREASONCODE_SHARED_SUBSCRIPTIONS_NOT_SUPPORTED = 158,
|
||||
MQTTREASONCODE_CONNECTION_RATE_EXCEEDED = 159,
|
||||
MQTTREASONCODE_MAXIMUM_CONNECT_TIME = 160,
|
||||
MQTTREASONCODE_SUBSCRIPTION_IDENTIFIERS_NOT_SUPPORTED = 161,
|
||||
MQTTREASONCODE_WILDCARD_SUBSCRIPTIONS_NOT_SUPPORTED = 162
|
||||
};
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#define DLLImport __declspec(dllimport)
|
||||
#define DLLExport __declspec(dllexport)
|
||||
#else
|
||||
#define DLLImport extern
|
||||
#define DLLExport __attribute__ ((visibility ("default")))
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Returns a printable string description of an MQTT V5 reason code.
|
||||
* @param value an MQTT V5 reason code.
|
||||
* @return the printable string description of the input reason code.
|
||||
* NULL if the code was not found.
|
||||
*/
|
||||
DLLExport const char* MQTTReasonCode_toString(enum MQTTReasonCodes value);
|
||||
|
||||
#endif
|
||||
39
src/remote/include/paho_mqtt_3c/MQTTSubscribe.h
Normal file
39
src/remote/include/paho_mqtt_3c/MQTTSubscribe.h
Normal file
@ -0,0 +1,39 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Xiang Rong - 442039 Add makefile to Embedded C client
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef MQTTSUBSCRIBE_H_
|
||||
#define MQTTSUBSCRIBE_H_
|
||||
|
||||
#if !defined(DLLImport)
|
||||
#define DLLImport
|
||||
#endif
|
||||
#if !defined(DLLExport)
|
||||
#define DLLExport
|
||||
#endif
|
||||
|
||||
DLLExport int MQTTSerialize_subscribe(unsigned char* buf, int buflen, unsigned char dup, unsigned short packetid,
|
||||
int count, MQTTString topicFilters[], int requestedQoSs[]);
|
||||
|
||||
DLLExport int MQTTDeserialize_subscribe(unsigned char* dup, unsigned short* packetid,
|
||||
int maxcount, int* count, MQTTString topicFilters[], int requestedQoSs[], unsigned char* buf, int len);
|
||||
|
||||
DLLExport int MQTTSerialize_suback(unsigned char* buf, int buflen, unsigned short packetid, int count, int* grantedQoSs);
|
||||
|
||||
DLLExport int MQTTDeserialize_suback(unsigned short* packetid, int maxcount, int* count, int grantedQoSs[], unsigned char* buf, int len);
|
||||
|
||||
|
||||
#endif /* MQTTSUBSCRIBE_H_ */
|
||||
46
src/remote/include/paho_mqtt_3c/MQTTSubscribeOpts.h
Normal file
46
src/remote/include/paho_mqtt_3c/MQTTSubscribeOpts.h
Normal file
@ -0,0 +1,46 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(SUBOPTS_H)
|
||||
#define SUBOPTS_H
|
||||
|
||||
/** The MQTT V5 subscribe options, apart from QoS which existed before V5. */
|
||||
typedef struct MQTTSubscribe_options
|
||||
{
|
||||
/** The eyecatcher for this structure. Must be MQSO. */
|
||||
char struct_id[4];
|
||||
/** The version number of this structure. Must be 0.
|
||||
*/
|
||||
int struct_version;
|
||||
/** To not receive our own publications, set to 1.
|
||||
* 0 is the original MQTT behaviour - all messages matching the subscription are received.
|
||||
*/
|
||||
unsigned char noLocal;
|
||||
/** To keep the retain flag as on the original publish message, set to 1.
|
||||
* If 0, defaults to the original MQTT behaviour where the retain flag is only set on
|
||||
* publications sent by a broker if in response to a subscribe request.
|
||||
*/
|
||||
unsigned char retainAsPublished;
|
||||
/** 0 - send retained messages at the time of the subscribe (original MQTT behaviour)
|
||||
* 1 - send retained messages on subscribe only if the subscription is new
|
||||
* 2 - do not send retained messages at all
|
||||
*/
|
||||
unsigned char retainHandling;
|
||||
} MQTTSubscribe_options;
|
||||
|
||||
#define MQTTSubscribe_options_initializer { {'M', 'Q', 'S', 'O'}, 0, 0, 0, 0 }
|
||||
|
||||
#endif
|
||||
38
src/remote/include/paho_mqtt_3c/MQTTUnsubscribe.h
Normal file
38
src/remote/include/paho_mqtt_3c/MQTTUnsubscribe.h
Normal file
@ -0,0 +1,38 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Xiang Rong - 442039 Add makefile to Embedded C client
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef MQTTUNSUBSCRIBE_H_
|
||||
#define MQTTUNSUBSCRIBE_H_
|
||||
|
||||
#if !defined(DLLImport)
|
||||
#define DLLImport
|
||||
#endif
|
||||
#if !defined(DLLExport)
|
||||
#define DLLExport
|
||||
#endif
|
||||
|
||||
DLLExport int MQTTSerialize_unsubscribe(unsigned char* buf, int buflen, unsigned char dup, unsigned short packetid,
|
||||
int count, MQTTString topicFilters[]);
|
||||
|
||||
DLLExport int MQTTDeserialize_unsubscribe(unsigned char* dup, unsigned short* packetid, int max_count, int* count, MQTTString topicFilters[],
|
||||
unsigned char* buf, int len);
|
||||
|
||||
DLLExport int MQTTSerialize_unsuback(unsigned char* buf, int buflen, unsigned short packetid);
|
||||
|
||||
DLLExport int MQTTDeserialize_unsuback(unsigned short* packetid, unsigned char* buf, int len);
|
||||
|
||||
#endif /* MQTTUNSUBSCRIBE_H_ */
|
||||
24
src/remote/include/paho_mqtt_3c/Messages.h
Normal file
24
src/remote/include/paho_mqtt_3c/Messages.h
Normal file
@ -0,0 +1,24 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2013 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(MESSAGES_H)
|
||||
#define MESSAGES_H
|
||||
|
||||
#include "Log.h"
|
||||
|
||||
const char* Messages_get(int, enum LOG_LEVELS);
|
||||
|
||||
#endif
|
||||
42
src/remote/include/paho_mqtt_3c/OsWrapper.h
Normal file
42
src/remote/include/paho_mqtt_3c/OsWrapper.h
Normal file
@ -0,0 +1,42 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2016, 2017 logi.cals GmbH
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Gunter Raidl - timer support for VxWorks
|
||||
* Rainer Poisel - reusability
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(OSWRAPPER_H)
|
||||
#define OSWRAPPER_H
|
||||
|
||||
#if defined(_WRS_KERNEL)
|
||||
#include <time.h>
|
||||
|
||||
#define lstat stat
|
||||
|
||||
typedef unsigned long useconds_t;
|
||||
void usleep(useconds_t useconds);
|
||||
|
||||
#define timersub(a, b, result) \
|
||||
do \
|
||||
{ \
|
||||
(result)->tv_sec = (a)->tv_sec - (b)->tv_sec; \
|
||||
(result)->tv_usec = (a)->tv_usec - (b)->tv_usec; \
|
||||
if ((result)->tv_usec < 0) \
|
||||
{ \
|
||||
--(result)->tv_sec; \
|
||||
(result)->tv_usec += 1000000L; \
|
||||
} \
|
||||
} while (0)
|
||||
#endif /* defined(_WRS_KERNEL) */
|
||||
|
||||
#endif /* OSWRAPPER_H */
|
||||
91
src/remote/include/paho_mqtt_3c/SHA1.h
Normal file
91
src/remote/include/paho_mqtt_3c/SHA1.h
Normal file
@ -0,0 +1,91 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2018 Wind River Systems, Inc. All Rights Reserved.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Keith Holman - initial implementation and documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(SHA1_H)
|
||||
#define SHA1_H
|
||||
|
||||
#if defined(OPENSSL)
|
||||
#include <openssl/sha.h>
|
||||
|
||||
/** SHA-1 Digest Length */
|
||||
#define SHA1_DIGEST_LENGTH SHA_DIGEST_LENGTH
|
||||
|
||||
#else /* if defined(OPENSSL) */
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#include <Windows.h>
|
||||
#include <WinCrypt.h>
|
||||
typedef struct SHA_CTX_S
|
||||
{
|
||||
HCRYPTPROV hProv;
|
||||
HCRYPTHASH hHash;
|
||||
} SHA_CTX;
|
||||
#else /* if defined(WIN32) || defined(WIN64) */
|
||||
|
||||
#include <stdint.h>
|
||||
typedef struct SHA_CTX_S {
|
||||
uint32_t h[5];
|
||||
union {
|
||||
uint32_t w[16];
|
||||
uint8_t buffer[64];
|
||||
};
|
||||
unsigned int size;
|
||||
unsigned int total;
|
||||
} SHA_CTX;
|
||||
#endif /* else if defined(WIN32) || defined(WIN64) */
|
||||
|
||||
#include <stddef.h>
|
||||
|
||||
/** SHA-1 Digest Length (number of bytes in SHA1) */
|
||||
#define SHA1_DIGEST_LENGTH (160/8)
|
||||
|
||||
/**
|
||||
* Initializes the SHA1 hashing algorithm
|
||||
*
|
||||
* @param[in,out] ctx hashing context structure
|
||||
*
|
||||
* @see SHA1_Update
|
||||
* @see SHA1_Final
|
||||
*/
|
||||
int SHA1_Init(SHA_CTX *ctx);
|
||||
|
||||
/**
|
||||
* Updates a block to the SHA1 hash
|
||||
*
|
||||
* @param[in,out] ctx hashing context structure
|
||||
* @param[in] data block of data to hash
|
||||
* @param[in] len length of block to hash
|
||||
*
|
||||
* @see SHA1_Init
|
||||
* @see SHA1_Final
|
||||
*/
|
||||
int SHA1_Update(SHA_CTX *ctx, const void *data, size_t len);
|
||||
|
||||
/**
|
||||
* Produce final SHA1 hash
|
||||
*
|
||||
* @param[out] md SHA1 hash produced (must be atleast
|
||||
* @p SHA1_DIGEST_LENGTH in length)
|
||||
* @param[in,out] ctx hashing context structure
|
||||
*
|
||||
* @see SHA1_Init
|
||||
* @see SHA1_Final
|
||||
*/
|
||||
int SHA1_Final(unsigned char *md, SHA_CTX *ctx);
|
||||
|
||||
#endif /* if defined(OPENSSL) */
|
||||
#endif /* SHA1_H */
|
||||
|
||||
52
src/remote/include/paho_mqtt_3c/SSLSocket.h
Normal file
52
src/remote/include/paho_mqtt_3c/SSLSocket.h
Normal file
@ -0,0 +1,52 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs, Allan Stockdill-Mander - initial implementation
|
||||
* Ian Craggs - SNI support
|
||||
* Ian Craggs - post connect checks and CApath
|
||||
*******************************************************************************/
|
||||
#if !defined(SSLSOCKET_H)
|
||||
#define SSLSOCKET_H
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#define ssl_mutex_type HANDLE
|
||||
#else
|
||||
#include <pthread.h>
|
||||
#include <semaphore.h>
|
||||
#define ssl_mutex_type pthread_mutex_t
|
||||
#endif
|
||||
|
||||
#include <openssl/ssl.h>
|
||||
#include "SocketBuffer.h"
|
||||
#include "Clients.h"
|
||||
|
||||
#define URI_SSL "ssl://"
|
||||
|
||||
/** if we should handle openssl initialization (bool_value == 1) or depend on it to be initalized externally (bool_value == 0) */
|
||||
void SSLSocket_handleOpensslInit(int bool_value);
|
||||
|
||||
int SSLSocket_initialize(void);
|
||||
void SSLSocket_terminate(void);
|
||||
int SSLSocket_setSocketForSSL(networkHandles* net, MQTTClient_SSLOptions* opts, const char* hostname, size_t hostname_len);
|
||||
|
||||
int SSLSocket_getch(SSL* ssl, int socket, char* c);
|
||||
char *SSLSocket_getdata(SSL* ssl, int socket, size_t bytes, size_t* actual_len);
|
||||
|
||||
int SSLSocket_close(networkHandles* net);
|
||||
int SSLSocket_putdatas(SSL* ssl, int socket, char* buf0, size_t buf0len, int count, char** buffers, size_t* buflens, int* frees);
|
||||
int SSLSocket_connect(SSL* ssl, int sock, const char* hostname, int verify, int (*cb)(const char *str, size_t len, void *u), void* u);
|
||||
|
||||
int SSLSocket_getPendingRead(void);
|
||||
int SSLSocket_continueWrite(pending_writes* pw);
|
||||
|
||||
#endif
|
||||
145
src/remote/include/paho_mqtt_3c/Socket.h
Normal file
145
src/remote/include/paho_mqtt_3c/Socket.h
Normal file
@ -0,0 +1,145 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial implementation and documentation
|
||||
* Ian Craggs - async client updates
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(SOCKET_H)
|
||||
#define SOCKET_H
|
||||
|
||||
#include <sys/types.h>
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#include <winsock2.h>
|
||||
#include <ws2tcpip.h>
|
||||
#define MAXHOSTNAMELEN 256
|
||||
#if !defined(SSLSOCKET_H)
|
||||
#undef EAGAIN
|
||||
#define EAGAIN WSAEWOULDBLOCK
|
||||
#undef EINTR
|
||||
#define EINTR WSAEINTR
|
||||
#undef EINPROGRESS
|
||||
#define EINPROGRESS WSAEINPROGRESS
|
||||
#undef EWOULDBLOCK
|
||||
#define EWOULDBLOCK WSAEWOULDBLOCK
|
||||
#undef ENOTCONN
|
||||
#define ENOTCONN WSAENOTCONN
|
||||
#undef ECONNRESET
|
||||
#define ECONNRESET WSAECONNRESET
|
||||
#undef ETIMEDOUT
|
||||
#define ETIMEDOUT WAIT_TIMEOUT
|
||||
#endif
|
||||
#define ioctl ioctlsocket
|
||||
#define socklen_t int
|
||||
#else
|
||||
#define INVALID_SOCKET SOCKET_ERROR
|
||||
#include <sys/socket.h>
|
||||
#if !defined(_WRS_KERNEL)
|
||||
#include <sys/param.h>
|
||||
#include <sys/time.h>
|
||||
#include <sys/select.h>
|
||||
#include <sys/uio.h>
|
||||
#else
|
||||
#include <selectLib.h>
|
||||
#endif
|
||||
#include <netinet/in.h>
|
||||
#include <netinet/tcp.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <netdb.h>
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#define ULONG size_t
|
||||
#endif
|
||||
|
||||
#include "mutex_type.h" /* Needed for mutex_type */
|
||||
|
||||
/** socket operation completed successfully */
|
||||
#define TCPSOCKET_COMPLETE 0
|
||||
#if !defined(SOCKET_ERROR)
|
||||
/** error in socket operation */
|
||||
#define SOCKET_ERROR -1
|
||||
#endif
|
||||
/** must be the same as SOCKETBUFFER_INTERRUPTED */
|
||||
#define TCPSOCKET_INTERRUPTED -22
|
||||
#define SSL_FATAL -3
|
||||
|
||||
#if !defined(INET6_ADDRSTRLEN)
|
||||
#define INET6_ADDRSTRLEN 46 /** only needed for gcc/cygwin on windows */
|
||||
#endif
|
||||
|
||||
|
||||
#if !defined(max)
|
||||
#define max(A,B) ( (A) > (B) ? (A):(B))
|
||||
#endif
|
||||
|
||||
#include "LinkedList.h"
|
||||
|
||||
/*BE
|
||||
def FD_SET
|
||||
{
|
||||
128 n8 "data"
|
||||
}
|
||||
|
||||
def SOCKETS
|
||||
{
|
||||
FD_SET "rset"
|
||||
FD_SET "rset_saved"
|
||||
n32 dec "maxfdp1"
|
||||
n32 ptr INTList "clientsds"
|
||||
n32 ptr INTItem "cur_clientsds"
|
||||
n32 ptr INTList "connect_pending"
|
||||
n32 ptr INTList "write_pending"
|
||||
FD_SET "pending_wset"
|
||||
}
|
||||
BE*/
|
||||
|
||||
|
||||
/**
|
||||
* Structure to hold all socket data for the module
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
fd_set rset, /**< socket read set (see select doc) */
|
||||
rset_saved; /**< saved socket read set */
|
||||
int maxfdp1; /**< max descriptor used +1 (again see select doc) */
|
||||
List* clientsds; /**< list of client socket descriptors */
|
||||
ListElement* cur_clientsds; /**< current client socket descriptor (iterator) */
|
||||
List* connect_pending; /**< list of sockets for which a connect is pending */
|
||||
List* write_pending; /**< list of sockets for which a write is pending */
|
||||
fd_set pending_wset; /**< socket pending write set for select */
|
||||
} Sockets;
|
||||
|
||||
|
||||
void Socket_outInitialize(void);
|
||||
void Socket_outTerminate(void);
|
||||
int Socket_getReadySocket(int more_work, struct timeval *tp, mutex_type mutex);
|
||||
int Socket_getch(int socket, char* c);
|
||||
char *Socket_getdata(int socket, size_t bytes, size_t* actual_len);
|
||||
int Socket_putdatas(int socket, char* buf0, size_t buf0len, int count, char** buffers, size_t* buflens, int* frees);
|
||||
void Socket_close(int socket);
|
||||
int Socket_new(const char* addr, size_t addr_len, int port, int* socket);
|
||||
|
||||
int Socket_noPendingWrites(int socket);
|
||||
char* Socket_getpeer(int sock);
|
||||
|
||||
void Socket_addPendingWrite(int socket);
|
||||
void Socket_clearPendingWrite(int socket);
|
||||
|
||||
typedef void Socket_writeComplete(int socket, int rc);
|
||||
void Socket_setWriteCompleteCallback(Socket_writeComplete*);
|
||||
|
||||
#endif /* SOCKET_H */
|
||||
84
src/remote/include/paho_mqtt_3c/SocketBuffer.h
Normal file
84
src/remote/include/paho_mqtt_3c/SocketBuffer.h
Normal file
@ -0,0 +1,84 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2014 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
* Ian Craggs, Allan Stockdill-Mander - SSL updates
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(SOCKETBUFFER_H)
|
||||
#define SOCKETBUFFER_H
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#include <winsock2.h>
|
||||
#else
|
||||
#include <sys/socket.h>
|
||||
#endif
|
||||
|
||||
#if defined(OPENSSL)
|
||||
#include <openssl/ssl.h>
|
||||
#endif
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
typedef WSABUF iobuf;
|
||||
#else
|
||||
typedef struct iovec iobuf;
|
||||
#endif
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int socket;
|
||||
unsigned int index;
|
||||
size_t headerlen;
|
||||
char fixed_header[5]; /**< header plus up to 4 length bytes */
|
||||
size_t buflen, /**< total length of the buffer */
|
||||
datalen; /**< current length of data in buf */
|
||||
char* buf;
|
||||
} socket_queue;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int socket, count;
|
||||
size_t total;
|
||||
#if defined(OPENSSL)
|
||||
SSL* ssl;
|
||||
#endif
|
||||
size_t bytes;
|
||||
iobuf iovecs[5];
|
||||
int frees[5];
|
||||
} pending_writes;
|
||||
|
||||
#define SOCKETBUFFER_COMPLETE 0
|
||||
#if !defined(SOCKET_ERROR)
|
||||
#define SOCKET_ERROR -1
|
||||
#endif
|
||||
#define SOCKETBUFFER_INTERRUPTED -22 /* must be the same value as TCPSOCKET_INTERRUPTED */
|
||||
|
||||
void SocketBuffer_initialize(void);
|
||||
void SocketBuffer_terminate(void);
|
||||
void SocketBuffer_cleanup(int socket);
|
||||
char* SocketBuffer_getQueuedData(int socket, size_t bytes, size_t* actual_len);
|
||||
int SocketBuffer_getQueuedChar(int socket, char* c);
|
||||
void SocketBuffer_interrupted(int socket, size_t actual_len);
|
||||
char* SocketBuffer_complete(int socket);
|
||||
void SocketBuffer_queueChar(int socket, char c);
|
||||
|
||||
#if defined(OPENSSL)
|
||||
void SocketBuffer_pendingWrite(int socket, SSL* ssl, int count, iobuf* iovecs, int* frees, size_t total, size_t bytes);
|
||||
#else
|
||||
void SocketBuffer_pendingWrite(int socket, int count, iobuf* iovecs, int* frees, size_t total, size_t bytes);
|
||||
#endif
|
||||
pending_writes* SocketBuffer_getWrite(int socket);
|
||||
int SocketBuffer_writeComplete(int socket);
|
||||
pending_writes* SocketBuffer_updateWrite(int socket, char* topic, char* payload);
|
||||
|
||||
#endif
|
||||
71
src/remote/include/paho_mqtt_3c/StackTrace.h
Normal file
71
src/remote/include/paho_mqtt_3c/StackTrace.h
Normal file
@ -0,0 +1,71 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2017 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef STACKTRACE_H_
|
||||
#define STACKTRACE_H_
|
||||
|
||||
#include <stdio.h>
|
||||
#include "Log.h"
|
||||
#include "Thread.h"
|
||||
|
||||
#if defined(NOSTACKTRACE)
|
||||
#define FUNC_ENTRY
|
||||
#define FUNC_ENTRY_NOLOG
|
||||
#define FUNC_ENTRY_MED
|
||||
#define FUNC_ENTRY_MAX
|
||||
#define FUNC_EXIT
|
||||
#define FUNC_EXIT_NOLOG
|
||||
#define FUNC_EXIT_MED
|
||||
#define FUNC_EXIT_MAX
|
||||
#define FUNC_EXIT_RC(x)
|
||||
#define FUNC_EXIT_MED_RC(x)
|
||||
#define FUNC_EXIT_MAX_RC(x)
|
||||
#else
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#define inline __inline
|
||||
#define FUNC_ENTRY StackTrace_entry(__FUNCTION__, __LINE__, TRACE_MINIMUM)
|
||||
#define FUNC_ENTRY_NOLOG StackTrace_entry(__FUNCTION__, __LINE__, -1)
|
||||
#define FUNC_ENTRY_MED StackTrace_entry(__FUNCTION__, __LINE__, TRACE_MEDIUM)
|
||||
#define FUNC_ENTRY_MAX StackTrace_entry(__FUNCTION__, __LINE__, TRACE_MAXIMUM)
|
||||
#define FUNC_EXIT StackTrace_exit(__FUNCTION__, __LINE__, NULL, TRACE_MINIMUM)
|
||||
#define FUNC_EXIT_NOLOG StackTrace_exit(__FUNCTION__, __LINE__, -1)
|
||||
#define FUNC_EXIT_MED StackTrace_exit(__FUNCTION__, __LINE__, NULL, TRACE_MEDIUM)
|
||||
#define FUNC_EXIT_MAX StackTrace_exit(__FUNCTION__, __LINE__, NULL, TRACE_MAXIMUM)
|
||||
#define FUNC_EXIT_RC(x) StackTrace_exit(__FUNCTION__, __LINE__, &x, TRACE_MINIMUM)
|
||||
#define FUNC_EXIT_MED_RC(x) StackTrace_exit(__FUNCTION__, __LINE__, &x, TRACE_MEDIUM)
|
||||
#define FUNC_EXIT_MAX_RC(x) StackTrace_exit(__FUNCTION__, __LINE__, &x, TRACE_MAXIMUM)
|
||||
#else
|
||||
#define FUNC_ENTRY StackTrace_entry(__func__, __LINE__, TRACE_MINIMUM)
|
||||
#define FUNC_ENTRY_NOLOG StackTrace_entry(__func__, __LINE__, -1)
|
||||
#define FUNC_ENTRY_MED StackTrace_entry(__func__, __LINE__, TRACE_MEDIUM)
|
||||
#define FUNC_ENTRY_MAX StackTrace_entry(__func__, __LINE__, TRACE_MAXIMUM)
|
||||
#define FUNC_EXIT StackTrace_exit(__func__, __LINE__, NULL, TRACE_MINIMUM)
|
||||
#define FUNC_EXIT_NOLOG StackTrace_exit(__func__, __LINE__, NULL, -1)
|
||||
#define FUNC_EXIT_MED StackTrace_exit(__func__, __LINE__, NULL, TRACE_MEDIUM)
|
||||
#define FUNC_EXIT_MAX StackTrace_exit(__func__, __LINE__, NULL, TRACE_MAXIMUM)
|
||||
#define FUNC_EXIT_RC(x) StackTrace_exit(__func__, __LINE__, &x, TRACE_MINIMUM)
|
||||
#define FUNC_EXIT_MED_RC(x) StackTrace_exit(__func__, __LINE__, &x, TRACE_MEDIUM)
|
||||
#define FUNC_EXIT_MAX_RC(x) StackTrace_exit(__func__, __LINE__, &x, TRACE_MAXIMUM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
void StackTrace_entry(const char* name, int line, enum LOG_LEVELS trace);
|
||||
void StackTrace_exit(const char* name, int line, void* return_value, enum LOG_LEVELS trace);
|
||||
|
||||
void StackTrace_printStack(FILE* dest);
|
||||
char* StackTrace_get(thread_id_type, char* buf, int bufsize);
|
||||
|
||||
#endif /* STACKTRACE_H_ */
|
||||
75
src/remote/include/paho_mqtt_3c/Thread.h
Normal file
75
src/remote/include/paho_mqtt_3c/Thread.h
Normal file
@ -0,0 +1,75 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial implementation
|
||||
* Ian Craggs, Allan Stockdill-Mander - async client updates
|
||||
* Ian Craggs - fix for bug #420851
|
||||
* Ian Craggs - change MacOS semaphore implementation
|
||||
*******************************************************************************/
|
||||
#include "MQTTClient.h"
|
||||
|
||||
#if !defined(THREAD_H)
|
||||
#define THREAD_H
|
||||
|
||||
#include "mutex_type.h" /* Needed for mutex_type */
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#include <windows.h>
|
||||
#define thread_type HANDLE
|
||||
#define thread_id_type DWORD
|
||||
#define thread_return_type DWORD
|
||||
#define thread_fn LPTHREAD_START_ROUTINE
|
||||
#define cond_type HANDLE
|
||||
#define sem_type HANDLE
|
||||
#undef ETIMEDOUT
|
||||
#define ETIMEDOUT WSAETIMEDOUT
|
||||
#else
|
||||
#include <pthread.h>
|
||||
|
||||
#define thread_type pthread_t
|
||||
#define thread_id_type pthread_t
|
||||
#define thread_return_type void*
|
||||
typedef thread_return_type (*thread_fn)(void*);
|
||||
typedef struct { pthread_cond_t cond; pthread_mutex_t mutex; } cond_type_struct;
|
||||
typedef cond_type_struct *cond_type;
|
||||
#if defined(OSX)
|
||||
#include <dispatch/dispatch.h>
|
||||
typedef dispatch_semaphore_t sem_type;
|
||||
#else
|
||||
#include <semaphore.h>
|
||||
typedef sem_t *sem_type;
|
||||
#endif
|
||||
|
||||
cond_type Thread_create_cond(void);
|
||||
int Thread_signal_cond(cond_type);
|
||||
int Thread_wait_cond(cond_type condvar, int timeout);
|
||||
int Thread_destroy_cond(cond_type);
|
||||
#endif
|
||||
|
||||
DLLExport thread_type Thread_start(thread_fn, void*);
|
||||
|
||||
DLLExport mutex_type Thread_create_mutex();
|
||||
DLLExport int Thread_lock_mutex(mutex_type);
|
||||
DLLExport int Thread_unlock_mutex(mutex_type);
|
||||
void Thread_destroy_mutex(mutex_type);
|
||||
|
||||
DLLExport thread_id_type Thread_getid();
|
||||
|
||||
sem_type Thread_create_sem(void);
|
||||
int Thread_wait_sem(sem_type sem, int timeout);
|
||||
int Thread_check_sem(sem_type sem);
|
||||
int Thread_post_sem(sem_type sem);
|
||||
int Thread_destroy_sem(sem_type sem);
|
||||
|
||||
|
||||
#endif
|
||||
115
src/remote/include/paho_mqtt_3c/Tree.h
Normal file
115
src/remote/include/paho_mqtt_3c/Tree.h
Normal file
@ -0,0 +1,115 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2013 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial implementation and documentation
|
||||
*******************************************************************************/
|
||||
|
||||
|
||||
#if !defined(TREE_H)
|
||||
#define TREE_H
|
||||
|
||||
#include <stdlib.h> /* for size_t definition */
|
||||
|
||||
/*BE
|
||||
defm defTree(T) // macro to define a tree
|
||||
|
||||
def T concat Node
|
||||
{
|
||||
n32 ptr T concat Node "parent"
|
||||
n32 ptr T concat Node "left"
|
||||
n32 ptr T concat Node "right"
|
||||
n32 ptr T id2str(T)
|
||||
n32 suppress "size"
|
||||
}
|
||||
|
||||
|
||||
def T concat Tree
|
||||
{
|
||||
struct
|
||||
{
|
||||
n32 ptr T concat Node suppress "root"
|
||||
n32 ptr DATA suppress "compare"
|
||||
}
|
||||
struct
|
||||
{
|
||||
n32 ptr T concat Node suppress "root"
|
||||
n32 ptr DATA suppress "compare"
|
||||
}
|
||||
n32 dec "count"
|
||||
n32 dec suppress "size"
|
||||
}
|
||||
|
||||
endm
|
||||
|
||||
defTree(INT)
|
||||
defTree(STRING)
|
||||
defTree(TMP)
|
||||
|
||||
BE*/
|
||||
|
||||
/**
|
||||
* Structure to hold all data for one list element
|
||||
*/
|
||||
typedef struct NodeStruct
|
||||
{
|
||||
struct NodeStruct *parent, /**< pointer to parent tree node, in case we need it */
|
||||
*child[2]; /**< pointers to child tree nodes 0 = left, 1 = right */
|
||||
void* content; /**< pointer to element content */
|
||||
size_t size; /**< size of content */
|
||||
unsigned int red : 1;
|
||||
} Node;
|
||||
|
||||
|
||||
/**
|
||||
* Structure to hold all data for one tree
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
struct
|
||||
{
|
||||
Node *root; /**< root node pointer */
|
||||
int (*compare)(void*, void*, int); /**< comparison function */
|
||||
} index[2];
|
||||
int indexes, /**< no of indexes into tree */
|
||||
count; /**< no of items */
|
||||
size_t size; /**< heap storage used */
|
||||
unsigned int heap_tracking : 1; /**< switch on heap tracking for this tree? */
|
||||
unsigned int allow_duplicates : 1; /**< switch to allow duplicate entries */
|
||||
} Tree;
|
||||
|
||||
|
||||
Tree* TreeInitialize(int(*compare)(void*, void*, int));
|
||||
void TreeInitializeNoMalloc(Tree* aTree, int(*compare)(void*, void*, int));
|
||||
void TreeAddIndex(Tree* aTree, int(*compare)(void*, void*, int));
|
||||
|
||||
void* TreeAdd(Tree* aTree, void* content, size_t size);
|
||||
|
||||
void* TreeRemove(Tree* aTree, void* content);
|
||||
|
||||
void* TreeRemoveKey(Tree* aTree, void* key);
|
||||
void* TreeRemoveKeyIndex(Tree* aTree, void* key, int index);
|
||||
|
||||
void* TreeRemoveNodeIndex(Tree* aTree, Node* aNode, int index);
|
||||
|
||||
void TreeFree(Tree* aTree);
|
||||
|
||||
Node* TreeFind(Tree* aTree, void* key);
|
||||
Node* TreeFindIndex(Tree* aTree, void* key, int index);
|
||||
|
||||
Node* TreeNextElement(Tree* aTree, Node* curnode);
|
||||
|
||||
int TreeIntCompare(void* a, void* b, int);
|
||||
int TreePtrCompare(void* a, void* b, int);
|
||||
int TreeStringCompare(void* a, void* b, int);
|
||||
|
||||
#endif
|
||||
7
src/remote/include/paho_mqtt_3c/VersionInfo.h.in
Normal file
7
src/remote/include/paho_mqtt_3c/VersionInfo.h.in
Normal file
@ -0,0 +1,7 @@
|
||||
#ifndef VERSIONINFO_H
|
||||
#define VERSIONINFO_H
|
||||
|
||||
#define BUILD_TIMESTAMP "@BUILD_TIMESTAMP@"
|
||||
#define CLIENT_VERSION "@CLIENT_VERSION@"
|
||||
|
||||
#endif /* VERSIONINFO_H */
|
||||
77
src/remote/include/paho_mqtt_3c/WebSocket.h
Normal file
77
src/remote/include/paho_mqtt_3c/WebSocket.h
Normal file
@ -0,0 +1,77 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2018 Wind River Systems, Inc. All Rights Reserved.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Keith Holman - initial implementation and documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(WEBSOCKET_H)
|
||||
#define WEBSOCKET_H
|
||||
|
||||
#include "Clients.h"
|
||||
|
||||
/**
|
||||
* WebSocket op codes
|
||||
* @{
|
||||
*/
|
||||
#define WebSocket_OP_CONTINUE 0x0 /* 0000 - continue frame */
|
||||
#define WebSocket_OP_TEXT 0x1 /* 0001 - text frame */
|
||||
#define WebSocket_OP_BINARY 0x2 /* 0010 - binary frame */
|
||||
#define WebSocket_OP_CLOSE 0x8 /* 1000 - close frame */
|
||||
#define WebSocket_OP_PING 0x9 /* 1001 - ping frame */
|
||||
#define WebSocket_OP_PONG 0xA /* 1010 - pong frame */
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* Various close status codes
|
||||
* @{
|
||||
*/
|
||||
#define WebSocket_CLOSE_NORMAL 1000
|
||||
#define WebSocket_CLOSE_GOING_AWAY 1001
|
||||
#define WebSocket_CLOSE_PROTOCOL_ERROR 1002
|
||||
#define WebSocket_CLOSE_UNKNOWN_DATA 1003
|
||||
#define WebSocket_CLOSE_RESERVED 1004
|
||||
#define WebSocket_CLOSE_NO_STATUS_CODE 1005 /* reserved: not to be used */
|
||||
#define WebSocket_CLOSE_ABNORMAL 1006 /* reserved: not to be used */
|
||||
#define WebSocket_CLOSE_BAD_DATA 1007
|
||||
#define WebSocket_CLOSE_POLICY 1008
|
||||
#define WebSocket_CLOSE_MSG_TOO_BIG 1009
|
||||
#define WebSocket_CLOSE_NO_EXTENSION 1010
|
||||
#define WebScoket_CLOSE_UNEXPECTED 1011
|
||||
#define WebSocket_CLOSE_TLS_FAIL 1015 /* reserved: not be used */
|
||||
/** @} */
|
||||
|
||||
/* closes a websocket connection */
|
||||
void WebSocket_close(networkHandles *net, int status_code, const char *reason);
|
||||
|
||||
/* sends upgrade request */
|
||||
int WebSocket_connect(networkHandles *net, const char *uri);
|
||||
|
||||
/* calculates the extra data required in a packet to hold a WebSocket frame header */
|
||||
size_t WebSocket_calculateFrameHeaderSize(networkHandles *net, int mask_data,
|
||||
size_t data_len);
|
||||
|
||||
/* obtain data from network socket */
|
||||
int WebSocket_getch(networkHandles *net, char* c);
|
||||
char *WebSocket_getdata(networkHandles *net, size_t bytes, size_t* actual_len);
|
||||
|
||||
/* send data out, in websocket format only if required */
|
||||
int WebSocket_putdatas(networkHandles* net, char* buf0, size_t buf0len,
|
||||
int count, char** buffers, size_t* buflens, int* freeData);
|
||||
|
||||
/* releases any resources used by the websocket system */
|
||||
void WebSocket_terminate(void);
|
||||
|
||||
/* handles websocket upgrade request */
|
||||
int WebSocket_upgrade(networkHandles *net);
|
||||
|
||||
#endif /* WEBSOCKET_H */
|
||||
25
src/remote/include/paho_mqtt_3c/mutex_type.h
Normal file
25
src/remote/include/paho_mqtt_3c/mutex_type.h
Normal file
@ -0,0 +1,25 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
*******************************************************************************/
|
||||
#if !defined(_MUTEX_TYPE_H_)
|
||||
#define _MUTEX_TYPE_H_
|
||||
|
||||
#if defined(WIN32) || defined(WIN64)
|
||||
#include <windows.h>
|
||||
#define mutex_type HANDLE
|
||||
#else
|
||||
#include <pthread.h>
|
||||
#define mutex_type pthread_mutex_t*
|
||||
#endif
|
||||
|
||||
#endif /* _MUTEX_TYPE_H_ */
|
||||
86
src/remote/include/paho_mqtt_3c/pubsub_opts.h
Normal file
86
src/remote/include/paho_mqtt_3c/pubsub_opts.h
Normal file
@ -0,0 +1,86 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2012, 2018 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial contribution
|
||||
* Guilherme Maciel Ferreira - add keep alive option
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(PUBSUB_OPTS_H)
|
||||
#define PUBSUB_OPTS_H
|
||||
|
||||
#include "MQTTAsync.h"
|
||||
#include "MQTTClientPersistence.h"
|
||||
|
||||
struct pubsub_opts
|
||||
{
|
||||
/* debug app options */
|
||||
int publisher; /* publisher app? */
|
||||
int quiet;
|
||||
int verbose;
|
||||
int tracelevel;
|
||||
char* delimiter;
|
||||
int maxdatalen;
|
||||
/* message options */
|
||||
char* message;
|
||||
char* filename;
|
||||
int stdin_lines;
|
||||
int stdlin_complete;
|
||||
int null_message;
|
||||
/* MQTT options */
|
||||
int MQTTVersion;
|
||||
char* topic;
|
||||
char* clientid;
|
||||
int qos;
|
||||
int retained;
|
||||
char* username;
|
||||
char* password;
|
||||
char* host;
|
||||
char* port;
|
||||
char* connection;
|
||||
int keepalive;
|
||||
/* will options */
|
||||
char* will_topic;
|
||||
char* will_payload;
|
||||
int will_qos;
|
||||
int will_retain;
|
||||
/* TLS options */
|
||||
int insecure;
|
||||
char* capath;
|
||||
char* cert;
|
||||
char* cafile;
|
||||
char* key;
|
||||
char* keypass;
|
||||
char* ciphers;
|
||||
/* MQTT V5 options */
|
||||
int message_expiry;
|
||||
struct {
|
||||
char *name;
|
||||
char *value;
|
||||
} user_property;
|
||||
};
|
||||
|
||||
typedef struct
|
||||
{
|
||||
const char* name;
|
||||
const char* value;
|
||||
} pubsub_opts_nameValue;
|
||||
|
||||
//void usage(struct pubsub_opts* opts, const char* version, const char* program_name);
|
||||
void usage(struct pubsub_opts* opts, pubsub_opts_nameValue* name_values, const char* program_name);
|
||||
int getopts(int argc, char** argv, struct pubsub_opts* opts);
|
||||
char* readfile(int* data_len, struct pubsub_opts* opts);
|
||||
void logProperties(MQTTProperties *props);
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
23
src/remote/include/paho_mqtt_3c/utf-8.h
Normal file
23
src/remote/include/paho_mqtt_3c/utf-8.h
Normal file
@ -0,0 +1,23 @@
|
||||
/*******************************************************************************
|
||||
* Copyright (c) 2009, 2013 IBM Corp.
|
||||
*
|
||||
* All rights reserved. This program and the accompanying materials
|
||||
* are made available under the terms of the Eclipse Public License v1.0
|
||||
* and Eclipse Distribution License v1.0 which accompany this distribution.
|
||||
*
|
||||
* The Eclipse Public License is available at
|
||||
* http://www.eclipse.org/legal/epl-v10.html
|
||||
* and the Eclipse Distribution License is available at
|
||||
* http://www.eclipse.org/org/documents/edl-v10.php.
|
||||
*
|
||||
* Contributors:
|
||||
* Ian Craggs - initial API and implementation and/or initial documentation
|
||||
*******************************************************************************/
|
||||
|
||||
#if !defined(UTF8_H)
|
||||
#define UTF8_H
|
||||
|
||||
int UTF8_validate(int len, const char *data);
|
||||
int UTF8_validateString(const char* string);
|
||||
|
||||
#endif
|
||||
2351
src/remote/include/remote/json.h
Normal file
2351
src/remote/include/remote/json.h
Normal file
File diff suppressed because it is too large
Load Diff
15
src/remote/include/remote/remote_node.hpp
Normal file
15
src/remote/include/remote/remote_node.hpp
Normal file
@ -0,0 +1,15 @@
|
||||
#ifndef __REMOTE_NODE_H__
|
||||
#define __REMOTE_NODE_H__
|
||||
|
||||
struct alignas(8) car_ctrl
|
||||
{
|
||||
int gear; // 挡位 0:N档,1:D档,2:R档
|
||||
float throttle; // 油门 0~65535
|
||||
float steering; // 转向 0~65535
|
||||
float brake; // 刹车 0~65535
|
||||
int sweep; // 清扫 1:清扫 0:不清扫
|
||||
};
|
||||
|
||||
extern car_ctrl car_ctrl_mes;
|
||||
|
||||
#endif
|
||||
BIN
src/remote/lib/libpaho-mqtt3c-static.a
Normal file
BIN
src/remote/lib/libpaho-mqtt3c-static.a
Normal file
Binary file not shown.
BIN
src/remote/lib/libpaho-mqtt3c.a
Normal file
BIN
src/remote/lib/libpaho-mqtt3c.a
Normal file
Binary file not shown.
22
src/remote/package.xml
Normal file
22
src/remote/package.xml
Normal file
@ -0,0 +1,22 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>remote</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="zxwl@todo.todo">zxwl</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>rclcpp</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>sweeper_interfaces</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
5342
src/remote/src/jsoncpp.cpp
Normal file
5342
src/remote/src/jsoncpp.cpp
Normal file
File diff suppressed because it is too large
Load Diff
282
src/remote/src/remote_node.cpp
Normal file
282
src/remote/src/remote_node.cpp
Normal file
@ -0,0 +1,282 @@
|
||||
#include "MQTTClient.h"
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "sweeper_interfaces/msg/mc_ctrl.hpp"
|
||||
#include "json.h"
|
||||
#include "remote_node.hpp"
|
||||
|
||||
#include <fstream>
|
||||
#include <iostream>
|
||||
#include <string>
|
||||
#include <chrono>
|
||||
#include <ctime>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <time.h>
|
||||
#include <sstream>
|
||||
#include <iomanip>
|
||||
#include <pthread.h>
|
||||
|
||||
namespace sweeperMsg = sweeper_interfaces::msg;
|
||||
|
||||
Json::Value root;
|
||||
Json::Reader reader;
|
||||
Json::Value data;
|
||||
std::string command;
|
||||
std::string remote_topic;
|
||||
int time_cunt = 0;
|
||||
// constexpr auto ADDRESS = "tcp://36.153.162.171:19583"; // 更改此处地址
|
||||
constexpr auto ADDRESS = "tcp://192.168.4.196:11883"; // 更改此处地址
|
||||
constexpr auto CLIENTID_REMOTE = "SWEEPER_CLIENT_REMOTE"; // 更改此处客户端ID
|
||||
|
||||
const char *getRemoteTopic()
|
||||
{
|
||||
return remote_topic.c_str();
|
||||
}
|
||||
|
||||
constexpr auto QOS = 1;
|
||||
constexpr auto TIMEOUT = 10000L;
|
||||
|
||||
volatile MQTTClient_deliveryToken deliveredtoken;
|
||||
|
||||
char remote_buff[500];
|
||||
|
||||
car_ctrl car_ctrl_mes;
|
||||
|
||||
void delivered(void *context, MQTTClient_deliveryToken dt)
|
||||
{
|
||||
(void)context;
|
||||
printf("Message with token value %d delivery confirmed\n", dt);
|
||||
deliveredtoken = dt;
|
||||
}
|
||||
|
||||
int msgarrvd(void *context, char *topicName, int topicLen, MQTTClient_message *message)
|
||||
{
|
||||
(void)context;
|
||||
(void)topicLen;
|
||||
time_cunt = 0;
|
||||
printf("Message arrived\n");
|
||||
printf("topic: %s\n", topicName);
|
||||
printf("message: %.*s\n", message->payloadlen, (char *)message->payload);
|
||||
|
||||
memset(remote_buff, 0, sizeof(remote_buff));
|
||||
memcpy(&remote_buff, (char *)message->payload, message->payloadlen);
|
||||
|
||||
root.clear();
|
||||
|
||||
if (!reader.parse(remote_buff, root))
|
||||
{
|
||||
printf("recv json fail\n");
|
||||
return 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << root << std::endl;
|
||||
|
||||
data = root["data"];
|
||||
command = root["command"].asString();
|
||||
|
||||
if (command.compare("gear") == 0)
|
||||
{
|
||||
car_ctrl_mes.gear = root["value"].asInt();
|
||||
}
|
||||
else if (command.compare("throttle") == 0)
|
||||
{
|
||||
car_ctrl_mes.throttle = root["value"].asFloat();
|
||||
}
|
||||
else if (command.compare("steering") == 0)
|
||||
{
|
||||
car_ctrl_mes.steering = root["value"].asFloat();
|
||||
}
|
||||
else if (command.compare("brake") == 0)
|
||||
{
|
||||
car_ctrl_mes.brake = root["value"].asFloat();
|
||||
}
|
||||
else if (command.compare("sweep") == 0)
|
||||
{
|
||||
car_ctrl_mes.sweep = root["value"].asInt();
|
||||
}
|
||||
}
|
||||
|
||||
MQTTClient_freeMessage(&message);
|
||||
MQTTClient_free(topicName);
|
||||
return 1;
|
||||
}
|
||||
|
||||
void connlost(void *context, char *cause)
|
||||
{
|
||||
(void)context;
|
||||
printf("\nConnection lost\n");
|
||||
printf("cause: %s\n", cause);
|
||||
}
|
||||
|
||||
void *mqtt_remote(void *arg)
|
||||
{
|
||||
(void)arg;
|
||||
MQTTClient client;
|
||||
// MQTTClient_deliveryToken token_d_m;
|
||||
|
||||
MQTTClient_connectOptions conn_opts = MQTTClient_connectOptions_initializer;
|
||||
// MQTTClient_message pubmsg_d_m = MQTTClient_message_initializer;
|
||||
const char *REMOTE_TOPIC = getRemoteTopic();
|
||||
|
||||
int rc;
|
||||
char *username = NULL;
|
||||
char *password = NULL;
|
||||
|
||||
if ((rc = MQTTClient_create(&client, ADDRESS, CLIENTID_REMOTE, MQTTCLIENT_PERSISTENCE_NONE, NULL)) != MQTTCLIENT_SUCCESS)
|
||||
{
|
||||
printf("Failed to create client, return code %d\n", rc);
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if ((rc = MQTTClient_setCallbacks(client, NULL, connlost, msgarrvd, delivered)) != MQTTCLIENT_SUCCESS)
|
||||
{
|
||||
printf("Failed to set callbacks, return code %d\n", rc);
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
conn_opts.keepAliveInterval = 20;
|
||||
conn_opts.cleansession = 1;
|
||||
conn_opts.username = username;
|
||||
conn_opts.password = password;
|
||||
|
||||
if ((rc = MQTTClient_connect(client, &conn_opts)) != MQTTCLIENT_SUCCESS)
|
||||
{
|
||||
printf("Failed to connect, return code %d\n", rc);
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
printf("Subscribing to topic %s\nfor client %s using QoS%d\n\n", REMOTE_TOPIC, CLIENTID_REMOTE, QOS);
|
||||
if ((rc = MQTTClient_subscribe(client, REMOTE_TOPIC, QOS)) != MQTTCLIENT_SUCCESS)
|
||||
{
|
||||
printf("Failed to subscribe, return code %d\n", rc);
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
while (1)
|
||||
{
|
||||
usleep(200000);
|
||||
}
|
||||
|
||||
if ((rc = MQTTClient_unsubscribe(client, REMOTE_TOPIC)) != MQTTCLIENT_SUCCESS)
|
||||
{
|
||||
printf("Failed to unsubscribe, return code %d\n", rc);
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if ((rc = MQTTClient_disconnect(client, 10000)) != MQTTCLIENT_SUCCESS)
|
||||
{
|
||||
printf("Failed to disconnect, return code %d\n", rc);
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
MQTTClient_destroy(&client);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
class remote_node : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
// 构造函数,有一个参数为节点名称
|
||||
remote_node(std::string name) : Node(name)
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "%s节点已经启动.", name.c_str());
|
||||
msg_publisher_ = this->create_publisher<sweeperMsg::McCtrl>("ctrl_command", 10);
|
||||
timer_ = this->create_wall_timer(std::chrono::milliseconds(100), std::bind(&remote_node::timer_callback, this));
|
||||
}
|
||||
|
||||
private:
|
||||
void timer_callback()
|
||||
{
|
||||
sweeperMsg::McCtrl message;
|
||||
message.gear = car_ctrl_mes.gear;
|
||||
if (car_ctrl_mes.gear == 0) // N档
|
||||
message.gear = 0;
|
||||
else if (car_ctrl_mes.gear == 1) // D档
|
||||
message.gear = 2;
|
||||
else if (car_ctrl_mes.gear == 2) // R档
|
||||
message.gear = 1;
|
||||
|
||||
// 刹车
|
||||
message.brake = (car_ctrl_mes.brake > 0) ? true : false;
|
||||
|
||||
// 油门 映射到 [0, 1000] 范围
|
||||
message.rpm = car_ctrl_mes.throttle / 65535.0f * 1000.0f;
|
||||
|
||||
// 转向
|
||||
// 0~32200 -> -40~0 33200~65535 -> 0~40
|
||||
float steering = 0;
|
||||
if (car_ctrl_mes.steering < 32200)
|
||||
{
|
||||
const double originalWidth1 = 32200.0;
|
||||
const double targetWidth1 = 40.0;
|
||||
|
||||
double unitLength1 = targetWidth1 / originalWidth1;
|
||||
|
||||
steering = -40 + static_cast<float>(car_ctrl_mes.steering * unitLength1);
|
||||
}
|
||||
else if (car_ctrl_mes.steering > 33200)
|
||||
{
|
||||
const double originalWidth2 = 32355.0; // 注意这里是从 33200 到 65535,共计 32355 个数
|
||||
const double targetWidth2 = 40.0;
|
||||
|
||||
double unitLength2 = targetWidth2 / originalWidth2;
|
||||
|
||||
steering = static_cast<float>((car_ctrl_mes.steering - 32200) * unitLength2);
|
||||
}
|
||||
else
|
||||
{
|
||||
steering = 0.0; // 朝向前方
|
||||
}
|
||||
message.angle = steering;
|
||||
|
||||
message.sweep = car_ctrl_mes.sweep;
|
||||
|
||||
msg_publisher_->publish(message);
|
||||
}
|
||||
|
||||
// 声名定时器指针
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
// 声明话题发布者指针
|
||||
rclcpp::Publisher<sweeperMsg::McCtrl>::SharedPtr msg_publisher_;
|
||||
};
|
||||
|
||||
void init_main()
|
||||
{
|
||||
Json::Reader reader;
|
||||
Json::Value root;
|
||||
std::ifstream in("config.json", std::ios::binary);
|
||||
if (!in.is_open())
|
||||
{
|
||||
std::cout << "read config file error" << std::endl;
|
||||
return;
|
||||
}
|
||||
if (reader.parse(in, root))
|
||||
{
|
||||
remote_topic = root["mqtt"]["remote_topic"].asString();
|
||||
}
|
||||
}
|
||||
|
||||
pthread_t mqtt_remote_thread_t;
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
init_main();
|
||||
memset(&car_ctrl_mes, 0, sizeof(car_ctrl_mes));
|
||||
pthread_create(&mqtt_remote_thread_t, NULL, mqtt_remote, NULL);
|
||||
|
||||
rclcpp::init(argc, argv);
|
||||
/*创建对应节点的共享指针对象*/
|
||||
auto node = std::make_shared<remote_node>("remote_node");
|
||||
/* 运行节点,并检测退出信号*/
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
}
|
||||
Loading…
Reference in New Issue
Block a user