28 using std::placeholders::_1;
40 OperationModes op_mode;
42 op_mode.value = OperationModes::UNKNOWN;
50 if (
msg.isDisconnect())
58 msg.checkStructuralIntegrity();
69 std::ostringstream os;
70 os <<
"Received Modbus message of unsupported API Version: " 74 os <<
"Can not determine OperationMode from Modbus message.";
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus messages arrives.
static OperationModes createUnknownOperationMode()
An abstraction of a series of filters which ensures that only Modbus messages with different timestam...
void updateOperationMode(const OperationModes &mode)
Stores the operation mode and publishes it, if it has changed.
Listens to the modbus_read topic and offers a service informing about the active operation mode...
Wrapper class to add semantic to a raw ModbusMsgInStamped.
const ModbusApiSpec api_spec_
ModbusAdapterOperationMode(ros::NodeHandle &nh, const ModbusApiSpec &api_spec)
Expection thrown upon construction of ModbusMsgWrapperBase of the message does not contain the requir...
#define ROS_ERROR_STREAM(args)
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED
Publishes information on the active operation mode. Also offers a service for querying the operation ...
Specifies the meaning of the holding registers.