ForceTorqueFilter.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <cstdint>
4 #include <ros/console.h>
5 #include <ros/node_handle.h>
6 
7 namespace rokubimini
8 {
9 namespace configuration
10 {
18 {
19 public:
20  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
27  ForceTorqueFilter() = default;
28 
40  ForceTorqueFilter(const uint16_t sincFilterSize, const uint8_t chopEnable, const uint8_t skipEnable,
41  const uint8_t fastEnable);
42 
43  ~ForceTorqueFilter() = default;
44 
54  bool load(const std::string& key, NodeHandlePtr nh);
55 
63  uint16_t getSincFilterSize() const
64  {
65  return sincFilterSize_;
66  }
67 
75  void setSincFilterSize(const uint16_t sincFilterSize)
76  {
77  sincFilterSize_ = sincFilterSize;
78  }
79 
87  uint8_t getChopEnable() const
88  {
89  return chopEnable_;
90  }
91 
99  void setChopEnable(const uint8_t chopEnable)
100  {
101  chopEnable_ = chopEnable;
102  }
103 
111  uint8_t getSkipEnable() const
112  {
113  return skipEnable_;
114  }
115 
123  void setSkipEnable(const uint8_t skipEnable)
124  {
125  skipEnable_ = skipEnable;
126  }
127 
135  uint8_t getFastEnable() const
136  {
137  return fastEnable_;
138  }
139 
147  void setFastEnable(const uint8_t fastEnable)
148  {
149  fastEnable_ = fastEnable;
150  }
151 
158  void print() const;
159 
160 private:
167  uint16_t sincFilterSize_;
168 
175  uint8_t chopEnable_;
176 
183  uint8_t skipEnable_;
184 
191  uint8_t fastEnable_;
192 };
193 
194 } // namespace configuration
195 } // namespace rokubimini
uint8_t getChopEnable() const
Gets the chopEnable variable.
Class holding the force-torque filter settings.
void setSincFilterSize(const uint16_t sincFilterSize)
Sets the sincFilterSize variable.
ForceTorqueFilter()=default
Default constructor.
void setFastEnable(const uint8_t fastEnable)
Sets the fastEnable variable.
uint16_t sincFilterSize_
The sincFilterSize variable.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
void setSkipEnable(const uint8_t skipEnable)
Sets the skipEnable variable.
uint8_t getFastEnable() const
Gets the fastEnable variable.
void print() const
Prints the existing Filter settings.
uint8_t getSkipEnable() const
Gets the skipEnable variable.
uint16_t getSincFilterSize() const
Gets the sincFilterSize variable.
bool load(const std::string &key, NodeHandlePtr nh)
Loads the force torque filter from the parameter server.
void setChopEnable(const uint8_t chopEnable)
Sets the chopEnable variable.
Tests Configuration.


rokubimini
Author(s):
autogenerated on Wed Mar 3 2021 03:09:12