29 #if defined(_USE_WIN_API) 32 #pragma comment(lib, "wsock32.lib") 33 #elif defined(_USE_LINUX_API) 34 #include <arpa/inet.h> 56 #define _BCAP_SERVER_MAX (BCAP_TCP_MAX + BCAP_UDP_MAX + BCAP_COM_MAX) 62 #define _FUNCTION_ID_MAX (137 + 1) 129 int i, start, end, index = -1;
148 for(i = start; i < end; i++) {
195 pPrev = bcap_param->
stack;
196 bcap_param->
stack = pObj;
224 for(i = 0; (i < bcap_param->
num_object) && (pCur); i++) {
237 bcap_param->
stack = pPrev;
271 for(i = 0; (i < bcap_param->
num_object) && (pCur); i++) {
272 if((pCur->
id ==
id) && (pCur->
hObj ==
hObj)) {
297 if(memcmp(tmp->device.arg, arg, size) == 0) {
324 flag_mutex = ((mutex != NULL) ? 1 : 0);
371 if(tmp != NULL) tmp->
node1 = node;
412 while (node != NULL) {
454 if(own->
node2 != NULL) {
462 if(tmp != NULL) tmp->
node1 = own;
466 while(node != NULL) {
500 child = parent->
node1;
501 while(child != NULL) {
534 send_packet->
argc = 0;
536 id = recv_packet->
id;
545 send_packet->
id = func(recv_packet->
args, recv_packet->
argc,
569 struct BCAP_PACKET tmp_send_packet, tmp_recv_packet, *send_packet =
580 tmp_recv_packet.
args = NULL;
583 hr =
bcap_recv(device, &tmp_recv_packet, 0);
587 memset(&tmp_send_packet, 0,
sizeof(
struct BCAP_PACKET));
592 switch(device->
type) {
596 if(tmp_param == NULL) {
609 tmp_param = bcap_param->
node1;
619 (tmp_recv_packet.
reserv == 0) ?
625 tmp_send_packet = *send_packet;
651 switch(tmp_recv_packet.
id) {
674 if((tmp_recv_packet.
argc >= 1) && (tmp_recv_packet.
args != NULL)) {
678 tmp_send_packet.
id = hr;
729 if(recv_packet->args != NULL) {
730 for(i = 0; i < recv_packet->argc; i++) {
733 free(recv_packet->args);
738 *recv_packet = tmp_recv_packet;
752 hr =
bcap_send(device, &tmp_send_packet);
774 if(relation_id > 0) {
778 pObj->
id = relation_id;
785 else if(relation_id < 0) {
788 0 : recv_packet->args[0].lVal);
805 if(
SUCCEEDED(hr) && (tmp_param != NULL)) {
818 if(tmp_recv_packet.
args != NULL) {
819 for(i = 0; i < tmp_recv_packet.
argc; i++) {
822 free(tmp_recv_packet.
args);
896 send_packet->
args = &vnt_send;
901 if(
FAILED(hr))
goto exit_proc;
905 if(
FAILED(hr))
goto exit_proc;
908 if(
FAILED(hr))
goto exit_proc;
939 if(recv_packet->args != NULL) {
940 for(i = 0; i < recv_packet->argc; i++) {
943 free(recv_packet->args);
995 if(
FAILED(hr))
goto exit_proc;
1024 child = bcap_param->
node1;
1025 while(child != NULL) {
1029 child = bcap_param->
node1;
1058 int type, index, *sock;
1069 if(connect == NULL || pfd == NULL)
1079 device = &bcap_param->
device;
1082 device->
type = type;
1083 switch(device->
type) {
1086 conn_param = ð_param;
1096 conn_param = ð_param;
1105 device->
arg = (
void *) paddr;
1114 conn_param = &com_param;
1128 if(device->
arg != NULL) {
1139 if(device->
arg != NULL) {
1148 sock = &device->
sock;
1149 hr = device->
dn_open(conn_param, sock);
1152 if(device->
arg != NULL) {
1196 if(bcap_param == NULL)
1199 device = &bcap_param->
device;
1200 sock = &device->
sock;
1213 if(device->
arg != NULL) {
#define S_FALSE
Succeeded but some processes may remain.
#define BCAP_UDP_MAX
A definition for the maximum count of UDP servers.
_DN_EXP_THREAD HRESULT wait_event(EVENT *pevt, uint32_t timeout)
Waits a event.
_DN_EXP_THREAD HRESULT unlock_mutex(MUTEX *pmutex)
Unlocks mutex handle.
#define ID_TASK_GETVARIABLE
b-CAP server communication object.
static struct CONN_BCAP_SERVER m_conn_param[_BCAP_SERVER_MAX]
static struct CONN_BCAP_SERVER * check_address(int index)
Checks whether the index has been used or not.
_BCAP_EXP_COMMON HRESULT bcap_recv(struct CONN_PARAM_COMMON *device, struct BCAP_PACKET *packet_recv, int client)
Receives b-CAP packet.
struct CONN_BCAP_SERVER * node1
#define S_EXECUTING
Succeeded but the server has been executing yet.
_DN_EXP_TCP HRESULT tcp_open_server(void *param, int *sock)
Opens TCP server.
static THRET THTYPE recv_thread(void *arg)
The receiving thread.
HRESULT(* dn_set_timeout)(int sock, uint32_t timeout)
struct VEC_OBJECT * stack
#define UDP_LIFELIMIT
A definition for the life limit of a UDP connection.
#define MIN_WDT_INTERVAL
A definition for the minimum watch dog timer interval.
HRESULT(* dn_recv)(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
#define ID_CONTROLLER_CONNECT
_DN_EXP_TCP HRESULT tcp_set_keepalive(int sock, int enable, uint32_t idle, uint32_t interval, uint32_t count)
Sets keep alive option.
#define KEEPALIVE_COUNT
A definition for the keep alive count option.
_DN_EXP_TCP HRESULT tcp_set_nodelay(int sock, int enable)
Sets no delay option.
_DN_EXP_THREAD HRESULT lock_mutex(MUTEX *pmutex, uint32_t timeout)
Locks mutex handle.
#define INIT_WDT_INTERVAL
A definition for the initial watch dog timer interval.
_DN_EXP_THREAD HRESULT create_event(EVENT *pevt, int reset_mode, int init_signal)
Creates a event object.
_DN_EXP_UDP HRESULT udp_send(int sock, const char *buf, uint32_t len_buf, void *arg)
Sends UDP packet.
#define _FUNCTION_ID_MAX
A definition for the maximum count of b-CAP function IDs.
static CALL_FUNC_BCAP m_list_func[_FUNCTION_ID_MAX]
_DN_EXP_THREAD HRESULT wait_event_multi(EVENT **pevt, uint32_t count, uint32_t timeout, int wait_all)
Waits multiple events.
struct CONN_PARAM_COMMON device
static int search_vector(struct CONN_BCAP_SERVER *bcap_param, int32_t id, uint32_t hObj)
Searches the target object with function ID and object handle.
Thread and mutex API file.
struct CONN_BCAP_SERVER * parent
#define FAILED(hr)
A macro that returns TRUE/FALSE. If hr is less than zero, then returns TRUE.
#define ID_CONTROLLER_GETMESSAGE
_DN_EXP_COM HRESULT com_open(void *param, int *sock)
Opens serial port.
static HRESULT pop_vector(struct CONN_BCAP_SERVER *bcap_param, struct VEC_OBJECT **pObj, int index)
Pops the object where is in the indicated index from the vector.
static uint32_t htonl(uint32_t hostlong)
#define E_HANDLE
Failed because the handle is invalid.
#define calc_time_diff(start, end)
A macro that calculates the time difference between start and end.
#define KEEPALIVE_ENABLE
A definition for the keep alive enable option.
_DN_EXP_UDP HRESULT udp_set_timeout(int sock, uint32_t timeout)
Sets timeout value to the UDP socket.
#define E_INVALIDARG
Failed because some arguments are invalid.
HRESULT(* dn_close)(int *sock)
#define ID_EXTENSION_GETVARIABLE
_DN_EXP_COM HRESULT com_set_timeout(int sock, uint32_t timeout)
Sets timeout value to the serial socket.
_DN_EXP_DEVICE HRESULT parse_conn_param_serial(const char *opt, struct CONN_PARAM_COM *param)
Parses serial connection parameters.
_DN_EXP_COMMON void SysFreeString(BSTR bstr)
Releases the memory of BSTR.
_DN_EXP_COM HRESULT com_recv(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Receives serial packet.
_DN_EXP_UDP HRESULT udp_open(void *param, int *sock)
Opens UDP socket.
_DN_EXP_THREAD HRESULT destroy_event(EVENT *pevt)
Destroys a event object.
#define ID_CONTROLLER_GETCOMMAND
static HRESULT bcap_callfunc(struct BCAP_PACKET *recv_packet, struct BCAP_PACKET *send_packet)
Execute a callback function with the received b-CAP command.
static THRET THTYPE exec_thread(void *arg)
The executing thread.
HRESULT bCap_Open_Server(const char *connect, uint32_t timeout, int *pfd)
Starts b-CAP server.
static THRET THTYPE accept_thread(void *arg)
The accepting thread for TCP connection.
_DN_EXP_COMMON HRESULT VariantCopy(VARIANT *pvargDest, const VARIANT *pvargSrc)
Copies the source variant to destination variant.
#define E_MAX_CONNECT
Failed because the number of connection is too much.
_DN_EXP_COM HRESULT com_close(int *sock)
Closes the socket.
#define E_OUTOFMEMORY
Failed because there is no enough memory space.
#define BCAP_COM_MAX
A definition for the maximum count of COM servers.
#define NOPARITY
A definition for serial communication setting.
HRESULT bCap_Close_Server(int *pfd)
Ends b-CAP server.
_DN_EXP_UDP HRESULT udp_recv(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Receives UDP packet.
#define SUCCEEDED(hr)
A macro that returns TRUE/FALSE. If hr is zero or more, then returns TRUE.
struct CONN_BCAP_SERVER * node2
_DN_EXP_THREAD HRESULT set_event(EVENT *pevt)
Sets a event.
#define INIT_EXEC_TIMEOUT
A definition for the initial executing timeout.
A type definition for Ethernet connection parameters.
#define ONESTOPBIT
A definition for serial communication setting.
#define ID_ROBOT_GETVARIABLE
#define INFINITE
A definition for infinite wait.
_DN_EXP_COMMON void VariantInit(VARIANT *pvarg)
Initializes the VARIANT.
_DN_EXP_COMMON HRESULT VariantChangeType(VARIANT *pvargDest, VARIANT *pvarSrc, uint16_t wFlags, uint16_t vt)
Changes the source variant to destination variant with the indicated type.
#define BCAP_OBJECT_MAX
A definition for the maximum count of creatable objects in a thread.
static const struct MAP_ID m_map_id[]
_DN_EXP_TCP HRESULT tcp_recv(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Receives TCP packet.
#define BCAP_TCP_MAX
A definition for the maximum count of TCP servers.
A type definition for common communication parameters.
static uint16_t htons(uint16_t hostshort)
static int check_lifelimit(struct CONN_BCAP_SERVER *parent)
Checks the life limit all of child nodes, and if expired then deletes.
_DN_EXP_THREAD uint32_t gettimeofday_msec()
Gets the current time value [ms].
HRESULT(* dn_open)(void *param, int *sock)
_DN_EXP_COM HRESULT com_send(int sock, const char *buf, uint32_t len_buf, void *arg)
Sends serial packet.
CHANGE_RELATION
change relation information.
HRESULT bCap_SetCallFunc(int32_t id, CALL_FUNC_BCAP func)
Sets a callback function.
#define _BCAP_SERVER_MAX
A definition for the maximum count of servers.
#define E_NOTIMPL
Failed because the function is not implemented.
A type definition for the multi type variable.
_DN_EXP_COMMON BSTR SysAllocString(const wchar_t *sz)
Allocates and returns BSTR.
struct BCAP_PACKET last_send
_DN_EXP_THREAD HRESULT release_mutex(MUTEX *pmutex)
Releases mutex handle.
_DN_EXP_COMMON void VariantClear(VARIANT *pvarg)
Clears the VARIANT.
#define E_MAX_OBJECT
Failed because the packet is too much.
#define begin_thread(p_thread, function, arg)
A macro that begins thread.
_DN_EXP_DEVICE int parse_conn_type(const char *opt)
Parses and returns the connection type.
A type definition for the b-CAP packet.
_DN_EXP_COMMON HRESULT GetOptionValue(BSTR bstrSrc, BSTR bstrKey, uint16_t vt, VARIANT *pvarDest)
Searchs the key string from source string and sets the value to the destination variant with the indi...
static int find_open_address(int type)
Returns the open address of m_conn_param.
A type definition for serial connection parameters.
static HRESULT receive_execute(struct CONN_BCAP_SERVER *bcap_param)
Receives the b-CAP packet and executes callback functions.
#define ID_CONTROLLER_GETEXTENSION
A vector for stacking created objects.
_DN_EXP_TCP HRESULT tcp_set_timeout(int sock, uint32_t timeout)
Sets timeout value to the TCP socket.
#define BCAP_CLIENT_MAX
A definition for the maximum count of TCP clients.
#define ID_CONTROLLER_GETTASK
HRESULT(* CALL_FUNC_BCAP)(VARIANT *vntArgs, int16_t Argc, VARIANT *vntRet)
struct BCAP_PACKET last_recv
#define ID_CONTROLLER_GETROBOT
_DN_EXP_TCP HRESULT tcp_send(int sock, const char *buf, uint32_t len_buf, void *arg)
Sends TCP packet.
#define exit_thread(thread)
A macro that ends thread.
#define ID_CONTROLLER_GETFILE
#define KEEPALIVE_IDLE
A definition for the keep alive idle option.
_DN_EXP_UDP HRESULT udp_close(int *sock)
Closes the socket.
_DN_EXP_TCP HRESULT tcp_accept(int sock, int *client)
TCP server accepts a TCP client.
#define E_BUSY_PROC
Failed because executing process is busy.
_DN_EXP_TCP HRESULT tcp_close(int *sock)
Closes the socket.
#define E_TIMEOUT
Failed because the communication timed out.
#define ID_FILE_GETVARIABLE
static int connect(SOCKET s, const struct sockaddr *name, int namelen)
HRESULT(* dn_send)(int sock, const char *buf, uint32_t len_buf, void *arg)
_BCAP_EXP_COMMON HRESULT bcap_send(struct CONN_PARAM_COMMON *device, struct BCAP_PACKET *packet_send)
Sends b-CAP packet.
_DN_EXP_DEVICE HRESULT parse_conn_param_ether(const char *opt, struct CONN_PARAM_ETH *param)
Parses Ethernet connection parameters.
#define KEEPALIVE_INTERVAL
A definition for the keep alive interval option.
_DN_EXP_THREAD HRESULT initialize_mutex(MUTEX *pmutex)
Initializes mutex handle.
static HRESULT push_vector(struct CONN_BCAP_SERVER *bcap_param, struct VEC_OBJECT *pObj)
Pushes the created object to the vector.
static HRESULT change_relation(struct CONN_BCAP_SERVER *own, int mode, int *sock)
Changes thread's relationships for TCP connection.
_DN_EXP_THREAD HRESULT reset_event(EVENT *pevt)
Resets a event.
#define ID_CONTROLLER_GETVARIABLE
static struct CONN_BCAP_SERVER * search_node(struct CONN_BCAP_SERVER *parent, const void *arg, int size)
Searches the target node which has a specified argument.