28 using std::placeholders::_1;
30 using namespace modbus_api::v3;
41 pilz_msgs::OperationModes op_mode;
43 op_mode.value = pilz_msgs::OperationModes::UNKNOWN;
51 if (
msg.isDisconnect())
59 msg.checkStructuralIntegrity();
70 std::ostringstream os;
71 os <<
"Received Modbus message of unsupported API Version: " <<
msg.getVersion()
74 os <<
"Can not determine OperationMode from Modbus message.";
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus messages arrives.
void updateOperationMode(const pilz_msgs::OperationModes &mode)
Stores the operation mode and publishes it, if it has changed.
static pilz_msgs::OperationModes createUnknownOperationMode()
static constexpr uint16_t MODBUS_API_VERSION_REQUIRED
An abstraction of a series of filters which ensures that only Modbus messages with different timestam...
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)
Publishes information on the active operation mode. Also offers a service for querying the operation ...
Specifies the meaning of the holding registers.