#include <modbus_tcp.hpp>
|
| void | configure () |
| |
| void | configureButtonHandler () |
| |
| void | displayMessageBoxHandler (const QString title, const QString text, const QString info, const QMessageBox::Icon icon) |
| |
| virtual void | load (const rviz::Config &config) |
| |
| void | newErrorHandler (const QString, const QString) |
| |
| bool | parseDataReg (const rviz::Config &config, const unsigned i, const unsigned j, const std::string name, industrial_modbus_tcp::Register &r) |
| |
| virtual void | save (rviz::Config config) const |
| |
| virtual void | saveDataReg (rviz::Config &config, const unsigned i, const unsigned j, const std::string name, const industrial_modbus_tcp::Register &r) const |
| |
Definition at line 22 of file modbus_tcp.hpp.
◆ ModbusTCP()
| industrial_modbus_tcp::ModbusTCP::ModbusTCP |
( |
QWidget * |
parent = NULL | ) |
|
◆ ~ModbusTCP()
| industrial_modbus_tcp::ModbusTCP::~ModbusTCP |
( |
| ) |
|
|
virtual |
◆ configure
| void industrial_modbus_tcp::ModbusTCP::configure |
( |
| ) |
|
|
protectedslot |
◆ configureButtonHandler
| void industrial_modbus_tcp::ModbusTCP::configureButtonHandler |
( |
| ) |
|
|
protectedslot |
◆ connectToService()
| void industrial_modbus_tcp::ModbusTCP::connectToService |
( |
| ) |
|
|
private |
◆ displayMessageBox
| void industrial_modbus_tcp::ModbusTCP::displayMessageBox |
( |
const QString |
, |
|
|
const QString |
, |
|
|
const QString |
, |
|
|
const QMessageBox::Icon |
|
|
) |
| |
|
signal |
◆ displayMessageBoxHandler
| void industrial_modbus_tcp::ModbusTCP::displayMessageBoxHandler |
( |
const QString |
title, |
|
|
const QString |
text, |
|
|
const QString |
info, |
|
|
const QMessageBox::Icon |
icon |
|
) |
| |
|
protectedslot |
◆ enable
| void industrial_modbus_tcp::ModbusTCP::enable |
( |
const bool |
| ) |
|
|
signal |
◆ errorsCallback()
| void industrial_modbus_tcp::ModbusTCP::errorsCallback |
( |
const std_msgs::String::ConstPtr & |
msg | ) |
|
|
private |
◆ load
| void industrial_modbus_tcp::ModbusTCP::load |
( |
const rviz::Config & |
config | ) |
|
|
protectedvirtualslot |
◆ newError
| void industrial_modbus_tcp::ModbusTCP::newError |
( |
const QString |
, |
|
|
const QString |
|
|
) |
| |
|
signal |
◆ newErrorHandler
| void industrial_modbus_tcp::ModbusTCP::newErrorHandler |
( |
const QString |
time, |
|
|
const QString |
msg |
|
) |
| |
|
protectedslot |
◆ parseDataReg
| bool industrial_modbus_tcp::ModbusTCP::parseDataReg |
( |
const rviz::Config & |
config, |
|
|
const unsigned |
i, |
|
|
const unsigned |
j, |
|
|
const std::string |
name, |
|
|
industrial_modbus_tcp::Register & |
r |
|
) |
| |
|
protectedslot |
◆ save
| void industrial_modbus_tcp::ModbusTCP::save |
( |
rviz::Config |
config | ) |
const |
|
protectedvirtualslot |
◆ saveDataReg
| void industrial_modbus_tcp::ModbusTCP::saveDataReg |
( |
rviz::Config & |
config, |
|
|
const unsigned |
i, |
|
|
const unsigned |
j, |
|
|
const std::string |
name, |
|
|
const industrial_modbus_tcp::Register & |
r |
|
) |
| const |
|
protectedvirtualslot |
◆ setStackIndex
| void industrial_modbus_tcp::ModbusTCP::setStackIndex |
( |
const int |
| ) |
|
|
signal |
◆ base_topic_
| std::string industrial_modbus_tcp::ModbusTCP::base_topic_ |
|
private |
◆ base_topic_line_edit_
| QLineEdit* industrial_modbus_tcp::ModbusTCP::base_topic_line_edit_ |
|
private |
◆ change_base_topic_
| QPushButton* industrial_modbus_tcp::ModbusTCP::change_base_topic_ |
|
private |
◆ configure_modbus_
◆ configure_modbus_srv_
| industrial_modbus_tcp::Configure industrial_modbus_tcp::ModbusTCP::configure_modbus_srv_ |
|
private |
◆ errors_log_
| QTableWidget* industrial_modbus_tcp::ModbusTCP::errors_log_ |
|
private |
◆ errors_sub_
◆ nh_
◆ stack_
| QStackedWidget* industrial_modbus_tcp::ModbusTCP::stack_ |
|
private |
The documentation for this class was generated from the following files: