git commit -m "first commit for v2"
This commit is contained in:
85
Devices/Libraries/Ros/delta_modbus/CMakeLists.txt
Executable file
85
Devices/Libraries/Ros/delta_modbus/CMakeLists.txt
Executable file
@@ -0,0 +1,85 @@
|
||||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(delta_modbus)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
std_msgs
|
||||
modbus_tcp
|
||||
diagnostic_msgs
|
||||
)
|
||||
|
||||
find_package(Boost REQUIRED COMPONENTS system)
|
||||
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES ${PROJECT_NAME}
|
||||
CATKIN_DEPENDS roscpp std_msgs modbus_tcp diagnostic_msgs
|
||||
DEPENDS Boost
|
||||
)
|
||||
|
||||
include_directories(
|
||||
include
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
add_library(${PROJECT_NAME} src/delta_modbus_tcp.cpp)
|
||||
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${GSTREAMER_LIBRARIES})
|
||||
|
||||
add_executable(test_delta test/test_delta.cpp)
|
||||
add_dependencies(test_delta ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
target_link_libraries(test_delta ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
# all install targets should use catkin DESTINATION variables
|
||||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
||||
|
||||
## Mark executable scripts (Python etc.) for installation
|
||||
## in contrast to setup.py, you can choose the destination
|
||||
# catkin_install_python(PROGRAMS
|
||||
# scripts/my_python_script
|
||||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark executables for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
|
||||
# install(TARGETS test_delta
|
||||
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark libraries for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
|
||||
install(TARGETS ${PROJECT_NAME}
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
## Mark cpp header files for installation
|
||||
install(DIRECTORY include/${PROJECT_NAME}/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
FILES_MATCHING PATTERN "*.h"
|
||||
PATTERN ".svn" EXCLUDE
|
||||
)
|
||||
|
||||
## Mark other files for installation (e.g. launch and bag files, etc.)
|
||||
install(FILES
|
||||
launch/test_delta.launch
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||
)
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
## Add gtest based cpp test target and link libraries
|
||||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_delta_modbus_tcp.cpp)
|
||||
# if(TARGET ${PROJECT_NAME}-test)
|
||||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
|
||||
# endif()
|
||||
|
||||
## Add folders to be run by python nosetests
|
||||
# catkin_add_nosetests(test)
|
||||
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
|
||||
9
Devices/Libraries/Ros/delta_modbus/launch/test_delta.launch
Executable file
9
Devices/Libraries/Ros/delta_modbus/launch/test_delta.launch
Executable file
@@ -0,0 +1,9 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<arg name="output_screen" default="screen"/>
|
||||
<arg name="path_yaml_file" default="$(find delta_modbus_tcp)/plc_config.yaml"/>
|
||||
|
||||
<node pkg="delta_modbus_tcp" type="test_delta" name="test_delta" output="$(arg output_screen)">
|
||||
<rosparam command="load" file="$(arg path_yaml_file)" />
|
||||
</node>
|
||||
</launch>
|
||||
73
Devices/Libraries/Ros/delta_modbus/package.xml
Executable file
73
Devices/Libraries/Ros/delta_modbus/package.xml
Executable file
@@ -0,0 +1,73 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>delta_modbus</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The delta_modbus_tcp package</description>
|
||||
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- Example: -->
|
||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||
<maintainer email="robotics@todo.todo">robotics</maintainer>
|
||||
|
||||
|
||||
<!-- One license tag required, multiple allowed, one license per tag -->
|
||||
<!-- Commonly used license strings: -->
|
||||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
|
||||
<license>TODO</license>
|
||||
|
||||
|
||||
<!-- Url tags are optional, but multiple are allowed, one per tag -->
|
||||
<!-- Optional attribute type can be: website, bugtracker, or repository -->
|
||||
<!-- Example: -->
|
||||
<!-- <url type="website">http://wiki.ros.org/delta_modbus_tcp</url> -->
|
||||
|
||||
|
||||
<!-- Author tags are optional, multiple are allowed, one per tag -->
|
||||
<!-- Authors do not have to be maintainers, but could be -->
|
||||
<!-- Example: -->
|
||||
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
|
||||
|
||||
|
||||
<!-- The *depend tags are used to specify dependencies -->
|
||||
<!-- Dependencies can be catkin packages or system dependencies -->
|
||||
<!-- Examples: -->
|
||||
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
|
||||
<!-- <depend>roscpp</depend> -->
|
||||
<!-- Note that this is equivalent to the following: -->
|
||||
<!-- <build_depend>roscpp</build_depend> -->
|
||||
<!-- <exec_depend>roscpp</exec_depend> -->
|
||||
<!-- Use build_depend for packages you need at compile time: -->
|
||||
<!-- <build_depend>message_generation</build_depend> -->
|
||||
<!-- Use build_export_depend for packages you need in order to build against this package: -->
|
||||
<!-- <build_export_depend>message_generation</build_export_depend> -->
|
||||
<!-- Use buildtool_depend for build tool packages: -->
|
||||
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
||||
<!-- Use exec_depend for packages you need at runtime: -->
|
||||
<!-- <exec_depend>message_runtime</exec_depend> -->
|
||||
<!-- Use test_depend for packages you need only for testing: -->
|
||||
<!-- <test_depend>gtest</test_depend> -->
|
||||
<!-- Use doc_depend for packages you need only for building documentation: -->
|
||||
<!-- <doc_depend>doxygen</doc_depend> -->
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>modbus_tcp</build_depend>
|
||||
<build_depend>diagnostic_msgs</build_depend>
|
||||
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<build_export_depend>modbus_tcp</build_export_depend>
|
||||
<build_export_depend>diagnostic_msgs</build_export_depend>
|
||||
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<exec_depend>modbus_tcp</exec_depend>
|
||||
<exec_depend>diagnostic_msgs</exec_depend>
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
|
||||
</export>
|
||||
</package>
|
||||
3
Devices/Libraries/Ros/delta_modbus/plc_config.yaml
Executable file
3
Devices/Libraries/Ros/delta_modbus/plc_config.yaml
Executable file
@@ -0,0 +1,3 @@
|
||||
IP: 192.168.2.100 # Địa chỉ HOST của thiết bị cua PLC
|
||||
PORT: 502 # Cổng PORT kết nối vớt PLC
|
||||
ID: 1 # Số ID của thiết bị mặc định là 1
|
||||
866
Devices/Libraries/Ros/delta_modbus/src/delta_modbus_tcp.cpp
Executable file
866
Devices/Libraries/Ros/delta_modbus/src/delta_modbus_tcp.cpp
Executable file
@@ -0,0 +1,866 @@
|
||||
#include "delta_modbus/delta_modbus_tcp.h"
|
||||
#include <boost/exception/all.hpp>
|
||||
|
||||
DELTA_NAMESPACE::PLC::PLC(std::string ip_address, int port, int id)
|
||||
: mb_(nullptr)
|
||||
{
|
||||
mb_ = boost::make_shared<modbus>(ip_address, port);
|
||||
mb_->modbus_set_slave_id(id);
|
||||
}
|
||||
|
||||
DELTA_NAMESPACE::PLC::~PLC()
|
||||
{
|
||||
mb_ = nullptr;
|
||||
}
|
||||
|
||||
void DELTA_NAMESPACE::PLC::connect(void) {
|
||||
ROS_INFO("Delta PLC is connecting.......");
|
||||
try
|
||||
{
|
||||
if(!mb_->modbus_connect()) {
|
||||
ROS_ERROR("Delta PLC connection is error");
|
||||
error_num = NOT_CONNECT_TO_PLC;
|
||||
} else {
|
||||
ros::Duration(0.5).sleep();
|
||||
error_num = PLC_RUN_OK;
|
||||
ROS_INFO("Delta PLC is Connected");
|
||||
}
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(e.what());
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
}
|
||||
|
||||
void DELTA_NAMESPACE::PLC::close()
|
||||
{
|
||||
try
|
||||
{
|
||||
mb_->modbus_close();
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(e.what());
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
}
|
||||
|
||||
bool DELTA_NAMESPACE::PLC::checkConnected()
|
||||
{
|
||||
try
|
||||
{
|
||||
return mb_->_connected;
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(e.what());
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::writeM(int M_number, const bool status) {
|
||||
try {
|
||||
if(M_number < M0_NUM || M_number > M4095_NUM) { throw AddressIsNotExistException(M_number); }
|
||||
if(M_number >= M0_NUM && M_number <= M1535_NUM) {
|
||||
return mb_->modbus_write_coil(M0_HEX + M_number, status);
|
||||
}
|
||||
else if(M_number >= M1536_NUM && M_number <= M4095_NUM) {
|
||||
return mb_->modbus_write_coil(M1536_HEX + M_number, status);
|
||||
}
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("delta::writeM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("delta::writeM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulWriteM(int start_number, int end_number, bool *status) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < M0_NUM || start_number > M4095_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < M0_NUM || end_number > M4095_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
|
||||
if(start_number >= M0_NUM && end_number <= M1535_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = status[i];
|
||||
return mb_->modbus_write_coils(M0_HEX + start_number, amount,value);
|
||||
}
|
||||
else if(start_number >= M1536_NUM && end_number <= M4095_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = status[start_number + i];
|
||||
return mb_->modbus_write_coils(M1536_HEX + start_number - M1535_NUM, amount, value);
|
||||
}
|
||||
else {
|
||||
int amount1,amount2;
|
||||
amount1 = M1535_NUM - start_number + 1;
|
||||
amount2 = end_number - M1536_NUM + 1;
|
||||
bool value1[amount1], value2[amount2];
|
||||
for(int i = 0; i < amount1; i++) value1[i] = status[i];
|
||||
for(int i = 0; i < amount2; i++) value2[i] = status[amount1 + i];
|
||||
int n1,n2;
|
||||
n1 = mb_->modbus_write_coils(M0_HEX + start_number,amount1,value1);
|
||||
n2 = mb_->modbus_write_coils(M1536_HEX, amount2,value2);
|
||||
return n1*n2;
|
||||
}
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("delta::mulWriteM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("delta::mulWriteM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception & e) {
|
||||
ROS_ERROR_STREAM("delta::mulWriteM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::setM(int M_number) {
|
||||
try {
|
||||
if(M_number < M0_NUM || M_number > M4095_NUM) { throw AddressIsNotExistException(M_number); }
|
||||
if(M_number >= M0_NUM && M_number <= M1535_NUM){
|
||||
return mb_->modbus_write_coil(M0_HEX + M_number, ON);
|
||||
}
|
||||
else if(M_number >= M1536_NUM && M_number <= M4095_NUM) {
|
||||
return mb_->modbus_write_coil(M1536_HEX + M_number, ON);
|
||||
}
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::setM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::setM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::resetM(int M_number) {
|
||||
try {
|
||||
if(M_number < M0_NUM || M_number > M4095_NUM) { throw AddressIsNotExistException(M_number); }
|
||||
if(M_number >= M0_NUM && M_number <= M1535_NUM){
|
||||
return mb_->modbus_write_coil(M0_HEX + M_number, OFF);
|
||||
}
|
||||
else if(M_number >= M1536_NUM && M_number <= M4095_NUM) {
|
||||
return mb_->modbus_write_coil(M1536_HEX + M_number, OFF);
|
||||
}
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::setM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::setM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulSetM(int start_number, int end_number) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < M0_NUM || start_number > M4095_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < M0_NUM || end_number > M4095_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
|
||||
if(start_number >= M0_NUM && end_number <= M1535_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = ON;
|
||||
return mb_->modbus_write_coils(M0_HEX + start_number, amount,value);
|
||||
}
|
||||
else if(start_number >= M1536_NUM && end_number <= M4095_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = ON;
|
||||
return mb_->modbus_write_coils(M1536_HEX + start_number - M1535_NUM, amount, value);
|
||||
}
|
||||
else {
|
||||
int amount1,amount2;
|
||||
amount1 = M1535_NUM - start_number + 1;
|
||||
amount2 = end_number - M1536_NUM + 1;
|
||||
bool value1[amount1], value2[amount2];
|
||||
for(int i = 0; i < amount1; i++) value1[i] = ON;
|
||||
for(int i = 0; i < amount2; i++) value2[i] = ON;
|
||||
int n1,n2;
|
||||
n1 = mb_->modbus_write_coils(M0_HEX + start_number,amount1,value1);
|
||||
n2 = mb_->modbus_write_coils(M1536_HEX, amount2,value2);
|
||||
return n1*n2;
|
||||
}
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulResetM(int start_number, int end_number) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < M0_NUM || start_number > M4095_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < M0_NUM || end_number > M4095_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
|
||||
if(start_number >= M0_NUM && end_number <= M1535_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = OFF;
|
||||
return mb_->modbus_write_coils(M0_HEX + start_number, amount,value);
|
||||
}
|
||||
else if(start_number >= M1536_NUM && end_number <= M4095_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = OFF;
|
||||
return mb_->modbus_write_coils(M1536_HEX + start_number - M1535_NUM, amount, value);
|
||||
}
|
||||
else {
|
||||
int amount1,amount2;
|
||||
amount1 = M1535_NUM - start_number + 1;
|
||||
amount2 = end_number - M1536_NUM + 1;
|
||||
bool value1[amount1], value2[amount2];
|
||||
for(int i = 0; i < amount1; i++) value1[i] = OFF;
|
||||
for(int i = 0; i < amount2; i++) value2[i] = OFF;
|
||||
int n1,n2;
|
||||
n1 = mb_->modbus_write_coils(M0_HEX + start_number,amount1,value1);
|
||||
n2 = mb_->modbus_write_coils(M1536_HEX, amount2,value2);
|
||||
return n1*n2;
|
||||
}
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::getM(int M_number, bool &buffer) {
|
||||
try {
|
||||
if(M_number < M0_NUM || M_number > M4095_NUM) { throw AddressIsNotExistException(M_number); }
|
||||
|
||||
if(M_number >= M0_NUM && M_number <= M1535_NUM)
|
||||
{
|
||||
return mb_->modbus_read_coil(M0_HEX + M_number, buffer);
|
||||
}
|
||||
else if(M_number >= M1536_NUM && M_number <= M4095_NUM){
|
||||
return mb_->modbus_read_coil(M1536_HEX + M_number, buffer);
|
||||
}
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::getM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::getM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulGetM(int start_number, int end_number, bool* buffer) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < M0_NUM || start_number > M4095_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < M0_NUM || end_number > M4095_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
|
||||
if(start_number >= M0_NUM && end_number <= M1535_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
return mb_->modbus_read_coils(M0_HEX + start_number, amount,buffer);
|
||||
}
|
||||
else if(start_number >= M1536_NUM && end_number <= M4095_NUM) {
|
||||
int amount = end_number - start_number + 1;
|
||||
return mb_->modbus_read_coils(M1536_HEX + start_number - M1535_NUM, amount,buffer);
|
||||
}
|
||||
else {
|
||||
int amount1,amount2;
|
||||
amount1 = M1535_NUM - start_number + 1;
|
||||
amount2 = end_number - M1536_NUM + 1;
|
||||
bool value1[amount1], value2[amount2];
|
||||
int n1,n2;
|
||||
n1 = mb_->modbus_read_coils(M0_HEX + start_number,amount1,value1);
|
||||
n2 = mb_->modbus_read_coils(M1536_HEX, amount2,value2);
|
||||
for(int i = 0; i < amount1; i++) buffer[i] = value1[i];
|
||||
for(int i = 0; i < amount2; i++) buffer[amount1 + i] = value2[i];
|
||||
return n1*n2;
|
||||
}
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetM: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::setY(int Y_number) {
|
||||
try {
|
||||
if(Y_number < Y0_NUM || Y_number > Y377_NUM) { throw AddressIsNotExistException(Y_number); }
|
||||
return mb_->modbus_write_coil(Y0_HEX + Y_number, ON);
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::setY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::setY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::resetY(int Y_number) {
|
||||
try {
|
||||
if(Y_number < Y0_NUM || Y_number > Y377_NUM) { throw AddressIsNotExistException(Y_number); }
|
||||
return mb_->modbus_write_coil(Y0_HEX + Y_number, OFF);
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::setY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::setY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulWriteY(int start_number, int end_number, bool *buffer) {
|
||||
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < Y0_NUM || start_number > Y377_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < Y0_NUM || end_number > Y377_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
return mb_->modbus_write_coils(Y0_HEX + start_number, amount, buffer);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulSetY(int start_number, int end_number) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < Y0_NUM || start_number > Y377_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < Y0_NUM || end_number > Y377_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = ON;
|
||||
return mb_->modbus_write_coils(Y0_HEX + start_number, amount, value);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulResetY(int start_number, int end_number) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < Y0_NUM || start_number > Y377_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < Y0_NUM || end_number > Y377_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
bool value[amount];
|
||||
for(int i = 0; i < amount; i++) value[i] = OFF;
|
||||
return mb_->modbus_write_coils(Y0_HEX + start_number, amount, value);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulGetY(int start_number, int end_number, bool *buffer) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < Y0_NUM || start_number > Y377_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < Y0_NUM || end_number > Y377_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
return mb_->modbus_read_coils(Y0_HEX + start_number, amount, buffer);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetY: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::getD(int D_number, uint16_t &buffer) {
|
||||
try
|
||||
{
|
||||
if(D_number < D0_NUM || D_number > D4095_NUM)
|
||||
throw AddressIsNotExistException(D_number);
|
||||
return mb_->modbus_read_holding_register(D0_HEX + D_number, buffer);
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::getD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::getD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulGetD(int start_number, int end_number, uint16_t *buffer) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < D0_NUM || start_number > D4095_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < D0_NUM || end_number > D4095_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
return mb_->modbus_read_holding_registers(D0_HEX + start_number, amount, buffer);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::setD(int D_number, int16_t &buffer) {
|
||||
try {
|
||||
if(D_number < D0_NUM || D_number > D4095_NUM) { throw AddressIsNotExistException(D_number); }
|
||||
return mb_->modbus_write_register(D0_HEX + D_number, buffer);
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::setD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::setD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulSetD(int start_number, int end_number, uint16_t *buffer) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < D0_NUM || start_number > D4095_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < D0_NUM || end_number > D4095_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
return mb_->modbus_write_registers(D0_HEX + start_number, amount, buffer);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulSetD: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::getX(int X_number, bool &buffer) {
|
||||
try {
|
||||
if(X_number < X0_NUM || X_number > X377_NUM) { throw AddressIsNotExistException(X_number); }
|
||||
mb_->modbus_read_input_bit(X0_HEX + X_number, buffer);
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::getX: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::getX: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* Read X bit
|
||||
* @param start_number Begin number X
|
||||
* @param end_number End number X
|
||||
* @param buffer Status of X
|
||||
*/
|
||||
int DELTA_NAMESPACE::PLC::mulGetX(int start_number, int end_number, bool* buffer) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < X0_NUM || start_number > X377_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < X0_NUM || end_number > X377_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
mb_->modbus_read_input_bits(X0_HEX + start_number, amount, buffer);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetX: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetX: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetX: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::getC(int C_number, uint16_t &buffer) {
|
||||
try {
|
||||
if(C_number < C0_NUM || C_number > C199_NUM) { throw AddressIsNotExistException(C_number); }
|
||||
mb_->modbus_read_holding_register(C0_HEX + C_number, buffer);
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::getC: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::getC: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DELTA_NAMESPACE::PLC::mulGetC(int start_number, int end_number, uint16_t *buffer) {
|
||||
try {
|
||||
if(start_number >= end_number) { throw CompareException(); }
|
||||
if(start_number < C0_NUM || start_number > C199_NUM) { throw AddressIsNotExistException(start_number); }
|
||||
if(end_number < C0_NUM || end_number > C199_NUM) { throw AddressIsNotExistException(end_number); }
|
||||
int amount = end_number - start_number + 1;
|
||||
mb_->modbus_read_holding_registers(C0_HEX + start_number, amount, buffer);
|
||||
}
|
||||
catch(CompareException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetC: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(AddressIsNotExistException & e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetC: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(std::exception& e) {
|
||||
ROS_ERROR_STREAM("PLC::mulGetC: " << e.what());
|
||||
ros::Duration(TIME_ERROR).sleep();
|
||||
return BAD_CON;
|
||||
}
|
||||
catch(const boost::exception& e)
|
||||
{
|
||||
ROS_ERROR_STREAM(boost::diagnostic_information(e));
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
ROS_ERROR_STREAM("Caught unknown exception");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
34
Devices/Libraries/Ros/delta_modbus/test/test_delta.cpp
Executable file
34
Devices/Libraries/Ros/delta_modbus/test/test_delta.cpp
Executable file
@@ -0,0 +1,34 @@
|
||||
#include <ros/ros.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include "delta_modbus/delta_modbus_tcp.h"
|
||||
#include <diagnostic_msgs/DiagnosticArray.h>
|
||||
|
||||
|
||||
/**********************************************************************
|
||||
* MAIN
|
||||
***********************************************************************/
|
||||
int main(int argc, char** argv) {
|
||||
ros::init(argc, argv, "test_delta_modbus_tcp");
|
||||
ros::NodeHandle nh("~");
|
||||
|
||||
std::string node_name = ros::this_node::getName();
|
||||
ROS_INFO("node_name: %s", node_name.c_str());
|
||||
|
||||
DELTA_NAMESPACE::PLC *plc = NULL;
|
||||
|
||||
std::string IP = "192.168.1.5";
|
||||
int PORT = 502;
|
||||
|
||||
plc = new DELTA_NAMESPACE::PLC(IP, PORT);
|
||||
plc->connect();
|
||||
|
||||
uint16_t D101;
|
||||
bool M[2];
|
||||
plc->getD(1, D101); plc->mulGetM(1, 2,M);
|
||||
ROS_INFO("D1 %d M1 %x %x", D101, M[0], M[1]);
|
||||
|
||||
ros::spin();
|
||||
plc = NULL;
|
||||
delete(plc);
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user