Go to the documentation of this file.00001 #ifndef EPOS_HARDWARE_UTILS_H_
00002 #define EPOS_HARDWARE_UTILS_H_
00003
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <stdint.h>
00008 #include "epos_library/Definitions.h"
00009 #include <boost/shared_ptr.hpp>
00010 #include <boost/weak_ptr.hpp>
00011
00012 bool SerialNumberFromHex(const std::string& str, uint64_t* serial_number);
00013
00014 int GetErrorInfo(unsigned int error_code, std::string* error_string);
00015
00016 int GetDeviceNameList(std::vector<std::string>* device_names, unsigned int* error_code);
00017
00018 int GetProtocolStackNameList(const std::string device_name, std::vector<std::string>* protocol_stack_names, unsigned int* error_code);
00019
00020 int GetInterfaceNameList(const std::string device_name, const std::string protocol_stack_name,
00021 std::vector<std::string>* interface_names, unsigned int* error_code);
00022
00023 int GetPortNameList(const std::string device_name, const std::string protocol_stack_name, const std::string interface_name,
00024 std::vector<std::string>* port_names, unsigned int* error_code);
00025
00026 int GetBaudrateList(const std::string device_name, const std::string protocol_stack_name, const std::string interface_name,
00027 const std::string port_name, std::vector<unsigned int>* port_names, unsigned int* error_code);
00028
00029
00030
00031 class DeviceHandle {
00032 public:
00033 DeviceHandle(void* ptr) : ptr(ptr) {}
00034 ~DeviceHandle() {
00035 unsigned int error_code;
00036 VCS_CloseDevice(const_cast<void*>(ptr), &error_code);
00037 }
00038 void* const ptr;
00039 };
00040 typedef boost::shared_ptr<DeviceHandle> DeviceHandlePtr;
00041
00042 class NodeHandle {
00043 public:
00044 NodeHandle(DeviceHandlePtr device_handle, unsigned short node_id)
00045 : device_handle(device_handle), node_id(node_id) {}
00046 const DeviceHandlePtr device_handle;
00047 const unsigned short node_id;
00048 };
00049 typedef boost::shared_ptr<NodeHandle> NodeHandlePtr;
00050
00051 typedef struct {
00052 std::string device_name;
00053 std::string protocol_stack_name;
00054 std::string interface_name;
00055 std::string port_name;
00056 unsigned short node_id;
00057 uint64_t serial_number;
00058 unsigned short hardware_version;
00059 unsigned short software_version;
00060 unsigned short application_number;
00061 unsigned short application_version;
00062 } EnumeratedNode;
00063
00064 class EposFactory {
00065 public:
00066
00067 EposFactory();
00068 DeviceHandlePtr CreateDeviceHandle(const std::string device_name,
00069 const std::string protocol_stack_name,
00070 const std::string interface_name,
00071 const std::string port_name,
00072 unsigned int* error_code);
00073
00074 NodeHandlePtr CreateNodeHandle(const std::string device_name,
00075 const std::string protocol_stack_name,
00076 const std::string interface_name,
00077 uint64_t serial_number,
00078 unsigned int* error_code);
00079
00080 NodeHandlePtr CreateNodeHandle(const EnumeratedNode& node,
00081 unsigned int* error_code);
00082
00083
00084 int EnumerateNodes(const std::string device_name, const std::string protocol_stack_name, const std::string interface_name,
00085 const std::string port_name, std::vector<EnumeratedNode>* devices, unsigned int* error_code);
00086
00087 int EnumerateNodes(const std::string device_name, const std::string protocol_stack_name, const std::string interface_name,
00088 std::vector<EnumeratedNode>* devices, unsigned int* error_code);
00089
00090
00091 private:
00092 std::map<std::string, boost::weak_ptr<DeviceHandle> > existing_handles;
00093 };
00094
00095
00096 #endif