modbus_adapter_operation_mode.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 
20 
21 #include <ros/time.h>
22 
23 #include <sstream>
24 #include <functional>
25 
26 namespace prbt_hardware_support
27 {
28 using std::placeholders::_1;
29 
30 using namespace modbus_api::v3;
31 
34  , api_spec_(api_spec)
35  , filter_pipeline_(new FilterPipeline(nh, std::bind(&ModbusAdapterOperationMode::modbusMsgCallback, this, _1)))
36 {
37 }
38 
40 {
41  pilz_msgs::OperationModes op_mode;
42  op_mode.time_stamp = ros::Time::now();
43  op_mode.value = pilz_msgs::OperationModes::UNKNOWN;
44  return op_mode;
45 }
46 
47 void ModbusAdapterOperationMode::modbusMsgCallback(const ModbusMsgInStampedConstPtr& msg_raw)
48 {
50 
51  if (msg.isDisconnect())
52  {
54  return;
55  }
56 
57  try
58  {
59  msg.checkStructuralIntegrity();
60  }
62  {
63  ROS_ERROR_STREAM(ex.what());
65  return;
66  }
67 
68  if (msg.getVersion() != MODBUS_API_VERSION_REQUIRED)
69  {
70  std::ostringstream os;
71  os << "Received Modbus message of unsupported API Version: " << msg.getVersion()
72  << ", required Version: " << MODBUS_API_VERSION_REQUIRED;
73  os << "\n";
74  os << "Can not determine OperationMode from Modbus message.";
75  ROS_ERROR_STREAM(os.str());
77  return;
78  }
79 
80  updateOperationMode(msg.getTimeStampedOperationMode());
81 }
82 
83 } // namespace prbt_hardware_support
msg
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 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.
ModbusAdapterOperationMode(ros::NodeHandle &nh, const ModbusApiSpec &api_spec)
Expection thrown upon construction of ModbusMsgWrapperBase of the message does not contain the requir...
static Time now()
#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.


prbt_hardware_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:34