git commit -m "first commit for v2"
This commit is contained in:
53
Devices/Libraries/Ros/delta_modbus/include/delta_modbus/delta_exception.h
Executable file
53
Devices/Libraries/Ros/delta_modbus/include/delta_modbus/delta_exception.h
Executable file
@@ -0,0 +1,53 @@
|
||||
#ifndef __DELTA_EXCEPTION_H_INCLUDE
|
||||
#define __DELTA_EXCEPTION_H_INCLUDE
|
||||
#include <iostream>
|
||||
#include <exception>
|
||||
using namespace std;
|
||||
|
||||
class CompareException : public std::exception {
|
||||
public:
|
||||
const char * what () const throw () {
|
||||
return "The first Address value must be less than the second Address value";
|
||||
}
|
||||
};
|
||||
|
||||
class AddressIsNotExistException : public std::exception {
|
||||
int Address;
|
||||
public:
|
||||
AddressIsNotExistException(int Address) {
|
||||
this->Address = Address;
|
||||
}
|
||||
|
||||
const char * what () const throw () {
|
||||
std::stringstream msg;
|
||||
msg << "The Addtess 0x" << Address << " is not Exist";
|
||||
return msg.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class OutRangeException : public std::exception {
|
||||
int Maximum;
|
||||
public:
|
||||
OutRangeException(int Maximum) {
|
||||
this->Maximum = Maximum;
|
||||
}
|
||||
|
||||
const char * what () const throw () {
|
||||
std::stringstream msg;
|
||||
msg << "Starting address must be 0 - 65535; quantity must be 0 - " << Maximum;
|
||||
return msg.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class Exception : public std::exception {
|
||||
int Maximum;
|
||||
public:
|
||||
std::string msg;
|
||||
Exception(std::string msg) {
|
||||
this->msg = msg;
|
||||
}
|
||||
const char * what () const throw () {
|
||||
return msg.c_str();
|
||||
}
|
||||
};
|
||||
#endif
|
||||
89
Devices/Libraries/Ros/delta_modbus/include/delta_modbus/delta_infomation.h
Executable file
89
Devices/Libraries/Ros/delta_modbus/include/delta_modbus/delta_infomation.h
Executable file
@@ -0,0 +1,89 @@
|
||||
#ifndef __DELTA_INFOMATION_H_INCLUDE_
|
||||
#define __DELTA_INFOMATION_H_INCLUDE_
|
||||
|
||||
#define PLC_RUN_OK 0X00
|
||||
#define NOT_CONNECT_TO_PLC 0X01
|
||||
#define PLC_NOT_RUN 0X02
|
||||
|
||||
#define DELTA_NAMESPACE_BEGIN namespace delta {
|
||||
#define DELTA_NAMESPACE delta
|
||||
#define DELTA_NAMESPACE_END }
|
||||
|
||||
#define ON true
|
||||
#define OFF false
|
||||
#define TIME_ERROR 5
|
||||
|
||||
#define S0_HEX 0x0001
|
||||
#define S1023_HEX 0x03FF
|
||||
#define S0_NUM 0
|
||||
#define S1023 1023
|
||||
|
||||
#define X0_HEX 0x0400
|
||||
#define X377_HEX 0x04FF
|
||||
#define X0_NUM 0
|
||||
#define X377_NUM 377
|
||||
|
||||
#define Y0_HEX 0x0500
|
||||
#define Y377_HEX 0x05FF
|
||||
#define Y0_NUM 0
|
||||
#define Y377_NUM 377
|
||||
|
||||
#define M0_HEX 0x0800
|
||||
#define M1535_HEX 0x0DFF
|
||||
#define M0_NUM 0
|
||||
#define M1535_NUM 1535
|
||||
|
||||
#define M1536_HEX 0xB000
|
||||
#define M4095_HEX 0xB9FF
|
||||
#define M1536_NUM 1536
|
||||
#define M4095_NUM 4095
|
||||
|
||||
#define C0_HEX 0x0E00
|
||||
#define C199_HEX 0x0EC7
|
||||
#define C0_NUM 0
|
||||
#define C199_NUM 199
|
||||
|
||||
#define D0_HEX 0x1000
|
||||
#define D4095_HEX 0x1FFF
|
||||
#define D0_NUM 0
|
||||
#define D4095_NUM 4095
|
||||
|
||||
#define READ_M_BITS 0x01
|
||||
#define READ_D_REGS 0x02
|
||||
#define READ_Y_BITS 0x03
|
||||
#define READ_X_BITS 0x04
|
||||
#define WRITE_M_BITS 0x05
|
||||
#define WRITE_D_REGS 0x06
|
||||
#define WRITE_Y_BITS 0x0F
|
||||
|
||||
enum DO_ {
|
||||
Y0 = 0 ,Y1 = 1 ,Y2 = 2 ,Y3 = 3 ,Y4 = 4 ,Y5 = 5 ,Y6 = 6 ,Y7 = 7 ,
|
||||
Y10 = 8 ,Y11 = 9 ,Y12 = 10 ,Y13 = 11 ,Y14 = 12 ,Y15 = 13 ,Y16 = 14 ,Y17 = 15 ,
|
||||
Y20 = 16 ,Y21 = 17 ,Y22 = 18 ,Y23 = 19 ,Y24 = 20 ,Y25 = 21 ,Y26 = 22 ,Y27 = 23 ,
|
||||
Y30 = 24 ,Y31 = 25 ,Y32 = 26 ,Y33 = 27 ,Y34 = 28 ,Y35 = 29 ,Y36 = 30 ,Y37 = 31 ,
|
||||
Y40 = 32 ,Y41 = 33 ,Y42 = 34 ,Y43 = 35 ,Y44 = 36 ,Y45 = 37 ,Y46 = 38 ,Y47 = 39 ,
|
||||
Y50 = 40 ,Y51 = 41 ,Y52 = 42 ,Y53 = 43 ,Y54 = 44 ,Y55 = 45 ,Y56 = 46 ,Y57 = 47 ,
|
||||
Y60 = 48 ,Y61 = 49 ,Y62 = 50 ,Y63 = 51 ,Y64 = 52 ,Y65 = 53 ,Y66 = 54 ,Y67 = 55 ,
|
||||
Y70 = 56 ,Y71 = 57 ,Y72 = 58 ,Y73 = 59 ,Y74 = 60 ,Y75 = 61 ,Y76 = 62 ,Y77 = 63 ,
|
||||
Y100 = 64 ,Y101 = 65 ,Y102 = 66 ,Y103 = 67 ,Y104 = 68 ,Y105 = 69 ,Y106 = 70 ,Y107 = 71 ,
|
||||
Y110 = 72 ,Y111 = 73 ,Y112 = 74 ,Y113 = 75 ,Y114 = 76 ,Y115 = 77 ,Y116 = 78 ,Y117 = 79 ,
|
||||
Y120 = 80 ,Y121 = 81 ,Y122 = 82 ,Y123 = 83 ,Y124 = 84 ,Y125 = 85 ,Y126 = 86 ,Y127 = 87 ,
|
||||
Y130 = 88 ,Y131 = 89 ,Y132 = 90 ,Y133 = 91 ,Y134 = 92 ,Y135 = 93 ,Y136 = 94 ,Y137 = 95
|
||||
};
|
||||
|
||||
enum DI_ {
|
||||
X0 = 0 ,X1 = 1 ,X2 = 2 ,X3 = 3 ,X4 = 4 ,X5 = 5 ,X6 = 6 ,X7 = 7 ,
|
||||
X10 = 8 ,X11 = 9 ,X12 = 10 ,X13 = 11 ,X14 = 12 ,X15 = 13 ,X16 = 14 ,X17 = 15 ,
|
||||
X20 = 16 ,X21 = 17 ,X22 = 18 ,X23 = 19 ,X24 = 20 ,X25 = 21 ,X26 = 22 ,X27 = 23 ,
|
||||
X30 = 24 ,X31 = 25 ,X32 = 26 ,X33 = 27 ,X34 = 28 ,X35 = 29 ,X36 = 30 ,X37 = 31 ,
|
||||
X40 = 32 ,X41 = 33 ,X42 = 34 ,X43 = 35 ,X44 = 36 ,X45 = 37 ,X46 = 38 ,X47 = 39 ,
|
||||
X50 = 40 ,X51 = 41 ,X52 = 42 ,X53 = 43 ,X54 = 44 ,X55 = 45 ,X56 = 46 ,X57 = 47 ,
|
||||
X60 = 48 ,X61 = 49 ,X62 = 50 ,X63 = 51 ,X64 = 52 ,X65 = 53 ,X66 = 54 ,X67 = 55 ,
|
||||
X70 = 56 ,X71 = 57 ,X72 = 58 ,X73 = 59 ,X74 = 60 ,X75 = 61 ,X76 = 62 ,X77 = 63 ,
|
||||
X100 = 64 ,X101 = 65 ,X102 = 66 ,X103 = 67 ,X104 = 68 ,X105 = 69 ,X106 = 70 ,X107 = 71 ,
|
||||
X110 = 72 ,X111 = 73 ,X112 = 74 ,X113 = 75 ,X114 = 76 ,X115 = 77 ,X116 = 78 ,X117 = 79 ,
|
||||
X120 = 80 ,X121 = 81 ,X122 = 82 ,X123 = 83 ,X124 = 84 ,X125 = 85 ,X126 = 86 ,X127 = 87 ,
|
||||
X130 = 88 ,X131 = 89 ,X132 = 90 ,X133 = 91 ,X134 = 92 ,X135 = 93 ,X136 = 94 ,X137 = 95
|
||||
};
|
||||
|
||||
#endif
|
||||
216
Devices/Libraries/Ros/delta_modbus/include/delta_modbus/delta_modbus_tcp.h
Executable file
216
Devices/Libraries/Ros/delta_modbus/include/delta_modbus/delta_modbus_tcp.h
Executable file
@@ -0,0 +1,216 @@
|
||||
#ifndef __DELTA_LIBRARY_H_INCLUDED
|
||||
#define __DELTA_LIBRARY_H_INCLUDED
|
||||
#include <ros/ros.h>
|
||||
#include <iostream>
|
||||
#include "modbus_tcp/modbus.h"
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include "delta_modbus/delta_infomation.h"
|
||||
#include "delta_modbus/delta_exception.h"
|
||||
|
||||
|
||||
DELTA_NAMESPACE_BEGIN
|
||||
class PLC
|
||||
{
|
||||
public:
|
||||
PLC(std::string ip_address, int port, int id = 1);
|
||||
|
||||
virtual ~PLC();
|
||||
|
||||
/**
|
||||
* @brief Connect to PLC
|
||||
*/
|
||||
void connect(void);
|
||||
|
||||
/**
|
||||
* @brief Close to PLC
|
||||
*/
|
||||
void close(void);
|
||||
|
||||
/**
|
||||
* @brief Checking PLC is connected
|
||||
*/
|
||||
bool checkConnected(void);
|
||||
|
||||
/**
|
||||
* @brief Write ON/OFF M Bit
|
||||
* @param M_number M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int writeM(int M_number, const bool status);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Set ON/OFF multiple M bit
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulWriteM(int start_number, int end_number, bool *status);
|
||||
|
||||
|
||||
/**
|
||||
* @brief SET ON M Bit
|
||||
* @param M_number M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int setM(int M_number);
|
||||
|
||||
/**
|
||||
* @brief SET OFF M Bit
|
||||
* @param M_number Node handle to get param for PLC
|
||||
* @return 0/-1
|
||||
*/
|
||||
int resetM(int M_number);
|
||||
|
||||
/**
|
||||
* @brief Set ON multiple M bit
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulSetM(int start_number, int end_number);
|
||||
|
||||
/**
|
||||
* @brief Set OFF multiple M bit
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulResetM(int start_number, int end_number);
|
||||
|
||||
/**
|
||||
* @brief Get load M Bit
|
||||
* @param M_number M bit
|
||||
* @param buffer Status of M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int getM(int M_number, bool &buffer);
|
||||
|
||||
/**
|
||||
* @brief Get load mul M bit
|
||||
* @param start_number Begin M bit
|
||||
* @param end_number End M bit
|
||||
* @param buffer Status of M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulGetM(int start_number, int end_number, bool* buffer);
|
||||
|
||||
/**
|
||||
* @brief Set On output Y
|
||||
* @param Y_number
|
||||
* @return 0/-1
|
||||
*/
|
||||
int setY(int Y_number);
|
||||
|
||||
/**
|
||||
* @brief Set Off output Y
|
||||
* @param Y_number
|
||||
* @return 0/-1
|
||||
*/
|
||||
int resetY(int Y_number);
|
||||
|
||||
/**
|
||||
* @brief Set multiple output Y is ON/OFF
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulWriteY(int start_number, int end_number, bool *buffer);
|
||||
|
||||
/**
|
||||
* @brief Set multiple output Y is ON
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulSetY(int start_number, int end_number);
|
||||
|
||||
/**
|
||||
* Set multiple output Y is OFF
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @return 0/-1
|
||||
*/
|
||||
int mulResetY(int start_number, int end_number);
|
||||
|
||||
/**
|
||||
* @brief Get status Y coils from start_number to end_number.
|
||||
* @param start_number begin M bit
|
||||
* @param end_number end M bit
|
||||
* @param buffer The status bit coils add to buffer
|
||||
*/
|
||||
int mulGetY(int start_number, int end_number, bool *buffer);
|
||||
|
||||
/**
|
||||
* @brief Read D register
|
||||
* @param D_number Number D
|
||||
* @param buffer Value of D_number
|
||||
*/
|
||||
int getD(int D_number, uint16_t &buffer);
|
||||
|
||||
/**
|
||||
* @brief Send data to D register
|
||||
* @param D_number Number D
|
||||
* @param buffer Value of D_number
|
||||
*/
|
||||
int mulGetD(int start_number, int end_number, uint16_t *buffer);
|
||||
|
||||
/**
|
||||
* @brief Send data to D register ()
|
||||
* @param start_number Begin D register
|
||||
* @param end_number End D register
|
||||
* @param buffer Buffer to store Data Read from Input Bits
|
||||
*/
|
||||
int setD(int D_number, int16_t &buffer);
|
||||
|
||||
/**
|
||||
* @brief Send data to D register ()
|
||||
* @param start_number Begin D register
|
||||
* @param end_number End D register
|
||||
* @param buffer Buffer to store Data Read from Input Bits
|
||||
*/
|
||||
int mulSetD(int start_number, int end_number, uint16_t *buffer);
|
||||
|
||||
/**
|
||||
* @brief Read X bit
|
||||
* @param X_number Number X
|
||||
* @param buffer Status of X
|
||||
*/
|
||||
int getX(int X_number, bool &buffer);
|
||||
|
||||
/**
|
||||
* @brief Read X bit
|
||||
* @param start_number Begin number X
|
||||
* @param end_number End number X
|
||||
* @param buffer Status of X
|
||||
*/
|
||||
int mulGetX(int start_number, int end_number, bool* buffer);
|
||||
|
||||
/**
|
||||
* @brief Read C register
|
||||
* @param C_number Number C
|
||||
* @param buffer Value of C_number
|
||||
*/
|
||||
int getC(int C_number, uint16_t &buffer);
|
||||
|
||||
/**
|
||||
* @brief Send data to C register ()
|
||||
* @param start_number Begin C register
|
||||
* @param end_number End C register
|
||||
* @param buffer Buffer to store Data Read from Input Bits
|
||||
*/
|
||||
int mulGetC(int start_number, int end_number, uint16_t *buffer);
|
||||
|
||||
/**
|
||||
* @brief get error information
|
||||
*/
|
||||
inline uint8_t getError();
|
||||
|
||||
private:
|
||||
/* Properties */
|
||||
uint8_t error_num;
|
||||
boost::shared_ptr<modbus> mb_;
|
||||
};
|
||||
DELTA_NAMESPACE_END
|
||||
|
||||
#endif
|
||||
Reference in New Issue
Block a user