18 #ifndef MODBUS_API_SPEC_H 19 #define MODBUS_API_SPEC_H 22 #include <initializer_list> 34 namespace modbus_api_spec
37 static const std::string
VERSION{
"VERSION" };
61 template <
class T = ros::NodeHandle>
67 for (
auto entry : reg_list)
69 setRegisterDefinition(entry.first, entry.second);
107 if (!nh.getParam(param_name, rpc))
109 throw ModbusApiSpecException(
"No api specified. (Expected at " + nh.getNamespace() +
"/" + param_name +
")");
112 for (
auto rpci = rpc.
begin(); rpci != rpc.
end(); ++rpci)
114 int value = rpci->second;
115 setRegisterDefinition(rpci->first.c_str(),
static_cast<unsigned short>(value));
121 return register_mapping_.find(key) != register_mapping_.end();
126 register_mapping_[key] = value;
133 return register_mapping_.at(key);
135 catch (
const std::out_of_range& e)
142 if (register_mapping_.empty())
147 typedef std::pair<std::string, unsigned short> RegisterMappingEntry;
151 auto it = std::min_element(
152 register_mapping_.begin(), register_mapping_.end(),
153 [](
const RegisterMappingEntry& a,
const RegisterMappingEntry& b) {
return a.second < b.second; });
160 if (register_mapping_.empty())
165 typedef std::pair<std::string, unsigned short> RegisterMappingEntry;
169 auto it = std::max_element(
170 register_mapping_.begin(), register_mapping_.end(),
171 [](
const RegisterMappingEntry& a,
const RegisterMappingEntry& b) {
return a.second < b.second; });
178 for (
auto it = register_mapping_.begin(); it != register_mapping_.end(); ++it)
180 registers.push_back(it->second);
181 std::sort(registers.begin(), registers.end());
185 inline std::map<std::string, unsigned short>::size_type
size()
const 187 return register_mapping_.size();
198 #endif // MODBUS_API_SPEC_H unsigned short getMinRegisterDefinition() const
static const std::string BRAKETEST_PERFORMED
static const std::string BRAKETEST_REQUEST
Expection thrown by prbt_hardware_support::ModbusApiSpec.
unsigned short getRegisterDefinition(const std::string &key) const
void getAllDefinedRegisters(std::vector< unsigned short > ®isters)
static const std::string BRAKETEST_RESULT
ModbusApiSpecTemplated ModbusApiSpec
Simple typedef for class like usage.
ModbusApiSpecTemplated(std::initializer_list< std::pair< std::string, unsigned short > > reg_list)
ModbusApiSpecTemplated(T &nh, const std::string ¶m_name)
Construct a new Modbus Api Spec Templated object.
unsigned short getMaxRegisterDefinition() const
static const std::string OPERATION_MODE
static const std::string READ_API_SPEC_PARAM_NAME
static const std::string RUN_PERMITTED
ModbusApiSpecException(const std::string &what_arg)
void setRegisterDefinition(const std::string &key, unsigned short value)
std::map< std::string, unsigned short >::size_type size() const
std::map< std::string, unsigned short > register_mapping_
bool hasRegisterDefinition(const std::string &key) const
Specifies the meaning of the holding registers.
static const std::string VERSION
ModbusApiSpecTemplated(T &nh)
Construct a new Modbus Api Spec Templated object.