modbus_adapter_run_permitted.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
19 
20 #include <sstream>
21 
23 
24 namespace prbt_hardware_support
25 {
26 
28  const ModbusApiSpec& api_spec)
29  : api_spec_(api_spec)
30  , update_run_permitted_(std::move(update_run_permitted_func))
31 {
32 }
33 
34 void ModbusAdapterRunPermitted::modbusMsgCallback(const ModbusMsgInStampedConstPtr& msg_raw)
35 {
37 
38  if(msg.isDisconnect())
39  {
40  ROS_ERROR("A disconnect from the modbus server happend.");
41  update_run_permitted_(false);
42  return;
43  }
44 
45  try
46  {
48  }
49  catch(const ModbusMsgWrapperException &e)
50  {
51  ROS_ERROR_STREAM(e.what());
52  update_run_permitted_(false);
53  return;
54  }
55 
57  {
58  std::ostringstream os;
59  os << "Received Modbus message of unsupported API Version: "
60  << msg.getVersion()
61  << ", required Version: " << MODBUS_API_VERSION_REQUIRED;
62  ROS_ERROR_STREAM(os.str());
63  update_run_permitted_(false);
64  return;
65  }
66 
68 }
69 
70 
71 } // namespace prbt_hardware_support
msg
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus messages arrives.
Wrapper class to add semantic to a raw ModbusMsgInStamped.
virtual void checkStructuralIntegrity() const override
Calls ModbusMsgWrapper::checkStructuralIntegrity().
bool getRunPermitted() const
Get the RUN_PERMITTED from the Modbus message.
ModbusAdapterRunPermitted(UpdateRunPermittedFunc &&update_run_permitted_func, const ModbusApiSpec &api_spec)
std::function< void(const bool)> UpdateRunPermittedFunc
bool isDisconnect() const
Check if the Modbus message informs about a disconnect from the server.
Expection thrown upon construction of ModbusMsgWrapperBase of the message does not contain the requir...
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
Specifies the meaning of the holding registers.


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:17