modbus_msg_in_builder.h
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 
18 #ifndef MODBUS_MSG_IN_BUILDER_H
19 #define MODBUS_MSG_IN_BUILDER_H
20 
21 #include <map>
22 
23 #include <std_msgs/MultiArrayLayout.h>
24 
25 #include <prbt_hardware_support/ModbusMsgInStamped.h>
28 
29 namespace prbt_hardware_support
30 {
31 
39 {
40 public:
41  ModbusMsgInBuilder(const ModbusApiSpec &api_spec);
42 
43 public:
44  void setRegister(const unsigned int register_n, const uint16_t value);
45 
46  ModbusMsgInBuilder& setRunPermitted(const uint16_t run_permitted);
47  ModbusMsgInBuilder& setOperationMode(const uint16_t mode);
48  ModbusMsgInBuilder& setApiVersion(const uint16_t version);
49 
50  ModbusMsgInStampedPtr build(const ros::Time &time) const;
51 
52 public:
57  static ModbusMsgInStampedPtr createDefaultModbusMsgIn(const std_msgs::MultiArrayLayout::_data_offset_type& offset,
58  const RegCont& holding_register);
59 
60  static void setDefaultLayout(std_msgs::MultiArrayLayout* layout,
61  const std_msgs::MultiArrayLayout::_data_offset_type& offset,
62  const RegCont::size_type& size);
63 
64 
65 private:
67  std::map<unsigned int, uint16_t> register_values_;
68 };
69 
70 // +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
71 inline ModbusMsgInBuilder& ModbusMsgInBuilder::setRunPermitted(const uint16_t run_permitted)
72 {
74  return *this;
75 }
76 
78 {
80  return *this;
81 }
82 
84 {
86  return *this;
87 }
88 
89 inline void ModbusMsgInBuilder::setRegister(const unsigned int register_n,
90  const uint16_t value)
91 {
92  register_values_[register_n] = value;
93 }
94 
95 }
96 
97 #endif // MODBUS_MSG_IN_BUILDER_H
ModbusMsgInStampedPtr build(const ros::Time &time) const
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
ModbusMsgInBuilder & setOperationMode(const uint16_t mode)
static const std::string OPERATION_MODE
ModbusMsgInBuilder(const ModbusApiSpec &api_spec)
static const std::string RUN_PERMITTED
static ModbusMsgInStampedPtr createDefaultModbusMsgIn(const std_msgs::MultiArrayLayout::_data_offset_type &offset, const RegCont &holding_register)
Creates a standard ModbusMsgIn which contains default values for all essential elements of the messag...
std::map< unsigned int, uint16_t > register_values_
Help on construction for ModbusMsgIn Messages.
unsigned short getRegisterDefinition(const std::string &key) const
static void setDefaultLayout(std_msgs::MultiArrayLayout *layout, const std_msgs::MultiArrayLayout::_data_offset_type &offset, const RegCont::size_type &size)
void setRegister(const unsigned int register_n, const uint16_t value)
ModbusMsgInBuilder & setRunPermitted(const uint16_t run_permitted)
ModbusMsgInBuilder & setApiVersion(const uint16_t version)
Specifies the meaning of the holding registers.


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