Rokubimini.cpp
Go to the documentation of this file.
1 // std
2 #include <chrono>
3 
4 // rokubimini
6 namespace rokubimini
7 {
9 {
10  std::string prefix = "rokubiminis/" + name_;
11  std::string product_name_string = prefix + "/product_name";
12  if (nh_->hasParam(product_name_string))
13  {
14  nh_->getParam(product_name_string, productName_);
15  }
16  else
17  {
18  ROS_ERROR("Could not find product name in Parameter Server: %s", product_name_string.c_str());
19  }
20 
21  configuration_.load(prefix, nh_);
22 }
23 
25 {
28  {
30  }
32  {
34  }
36  {
38  }
40  {
42  }
44  {
46  }
48  {
50  }
52  {
54  }
55 
57  {
59  }
60 
62  {
64  {
66  }
67  }
69 }
70 
72 {
73 }
74 
76 {
77  // stateMachine_.clearGoalStateEnum();
78 }
79 
81 {
82  for (const auto& error_cb : errorCbs_)
83  {
84  error_cb.second(getName());
85  }
86 }
87 
89 {
91  for (const auto& error_recovered_cb : errorRecoveredCbs_)
92  {
93  error_recovered_cb.second(getName());
94  }
95 }
96 
98 {
99  return true;
100  // return getStatusword().getStateEnum() == fsm::StateEnum::Error;
101 }
102 
104 {
105  for (const auto& fatal_cb : fatalCbs_)
106  {
107  fatal_cb.second(getName());
108  }
109 }
110 
112 {
114  for (const auto& fatal_recovered_cb : fatalRecoveredCbs_)
115  {
116  fatal_recovered_cb.second(getName());
117  }
118 }
119 
121 {
122  return true;
123  // return getStatusword().getStateEnum() == fsm::StateEnum::Fatal;
124 }
125 
127 {
128  statuswordRequested_ = false;
130  for (const auto& device_disconnected_cb : deviceDisconnectedCbs_)
131  {
132  device_disconnected_cb.second(getName());
133  }
134 
135  // Set statusword and reading accordingly.
136  // statusword_.resetData();
137  Reading reading;
138  const auto& stamp = ros::Time::now();
139  {
140  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
141  reading_.getWrench().header.stamp = stamp;
142  reading_.getImu().header.stamp = stamp;
144  if (getConfiguration().getSetReadingToNanOnDisconnect())
145  {
146  reading_.getWrench().wrench.force.x = NAN_VALUE;
147  reading_.getWrench().wrench.force.y = NAN_VALUE;
148  reading_.getWrench().wrench.force.z = NAN_VALUE;
149  reading_.getWrench().wrench.torque.x = NAN_VALUE;
150  reading_.getWrench().wrench.torque.y = NAN_VALUE;
151  reading_.getWrench().wrench.torque.z = NAN_VALUE;
152 
153  reading_.getImu().angular_velocity.x = NAN_VALUE;
154  reading_.getImu().angular_velocity.y = NAN_VALUE;
155  reading_.getImu().angular_velocity.z = NAN_VALUE;
156  reading_.getImu().linear_acceleration.x = NAN_VALUE;
157  reading_.getImu().linear_acceleration.y = NAN_VALUE;
158  reading_.getImu().linear_acceleration.z = NAN_VALUE;
159  }
160  reading = reading_;
161  }
162 
163  // External reading callbacks.
164  for (const auto& reading_cb : readingCbs_)
165  {
166  reading_cb.second(getName(), reading);
167  }
168 }
169 
171 {
172  // setGoalStateEnum(getConfiguration().getGoalStateEnumStartup());
173  for (const auto& device_reconnected_cb : deviceReconnectedCbs_)
174  {
175  device_reconnected_cb.second(getName());
176  }
177 }
178 
180 {
181  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
182  return reading_;
183 }
184 
185 void Rokubimini::getReading(Reading& reading) const
186 {
187  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
188  reading = reading_;
189 }
190 
192 {
193  // If the stamp has not changed, we assume it is again the same statusword.
194  if (statusword.getStamp() == statusword_.getStamp())
195  {
196  return;
197  }
198 
199  // Check if statusword contains new data.
200  if (statusword_.isEmpty() || statusword.getData() != statusword_.getData())
201  {
202  ROS_DEBUG_STREAM("Received new statusword (" << statusword << ").");
203  std::vector<std::string> infos;
204  std::vector<std::string> warnings;
205  std::vector<std::string> errors;
206  std::vector<std::string> fatals;
207  statusword.getMessagesDiff(statusword_, infos, warnings, errors, fatals);
208  for (const std::string& info : infos)
209  {
210  ROS_INFO_STREAM("[" << name_.c_str() << "] " << info);
211  }
212  for (const std::string& warning : warnings)
213  {
214  ROS_WARN_STREAM("[" << name_.c_str() << "] " << warning);
215  }
216  for (const std::string& error : errors)
217  {
218  ROS_ERROR_STREAM("[" << name_.c_str() << "] " << error);
219  }
220  for (const std::string& fatal : fatals)
221  {
222  ROS_ERROR_STREAM("[" << name_.c_str() << "] " << fatal);
223  }
224  }
225 
226  // Always update statusword to set new time stamp.
227  statusword_ = statusword;
228 }
229 
230 } // namespace rokubimini
rokubimini::Statusword::getData
uint32_t getData() const
Gets the data variable.
Definition: Statusword.cpp:63
rokubimini::Rokubimini::setAngularRateFilter
virtual bool setAngularRateFilter(const unsigned int filter)=0
Sets an angular rate filter to the device. It's virtual since it's implementation-specific.
rokubimini::Rokubimini::deviceIsInErrorState
bool deviceIsInErrorState()
Checks if the device is in error state.
Definition: Rokubimini.cpp:97
rokubimini::Rokubimini::startupWithoutCommunication
void startupWithoutCommunication()
Starts up a Rokubimini device before communication has been established by the BusManager.
Definition: Rokubimini.cpp:71
rokubimini::configuration::Configuration::getImuAccelerationFilter
unsigned int getImuAccelerationFilter() const
Definition: Configuration.cpp:333
rokubimini::configuration::Configuration::hasImuAccelerationRange
bool hasImuAccelerationRange() const
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configurati...
Definition: Configuration.cpp:423
rokubimini::Rokubimini::statuswordRequested_
std::atomic< bool > statuswordRequested_
Flag indicating if a statusword has been actively requested.
Definition: Rokubimini.hpp:649
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
rokubimini::Rokubimini::getConfiguration
configuration::Configuration & getConfiguration()
Non-const version of getConfiguration() const. Gets the Configuration of the device.
Definition: Rokubimini.hpp:82
rokubimini::Rokubimini::setForceTorqueOffset
virtual bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)=0
Sets a force torque offset to the device. It's virtual since it's implementation-specific.
rokubimini::Rokubimini::reading_
Reading reading_
The reading of the device.
Definition: Rokubimini.hpp:665
rokubimini::Reading::setStatusword
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
Definition: Reading.hpp:143
rokubimini::configuration::Configuration::getUseCustomCalibration
bool getUseCustomCalibration() const
Gets the useCustomCalibration variable.
Definition: Configuration.cpp:273
rokubimini::Rokubimini::setAccelerationFilter
virtual bool setAccelerationFilter(const unsigned int filter)=0
Sets an acceleration filter to the device. It's virtual since it's implementation-specific.
rokubimini::Rokubimini::load
virtual void load()
Loads the rokubimini configuration from the parameter server.
Definition: Rokubimini.cpp:8
rokubimini::configuration::Configuration::getForceTorqueFilter
const ForceTorqueFilter & getForceTorqueFilter() const
Gets the forceTorqueFilter variable.
Definition: Configuration.cpp:249
rokubimini::Reading::getImu
const ImuType & getImu() const
Gets the imu variable.
Definition: Reading.hpp:58
rokubimini::Rokubimini::getName
std::string getName() const
Gets the name of the device.
Definition: Rokubimini.hpp:70
rokubimini::Rokubimini::errorRecoveredCb
void errorRecoveredCb()
Calls the callbacks in the error recovered callbacks list.
Definition: Rokubimini.cpp:88
rokubimini::configuration::Configuration::getImuAccelerationRange
uint8_t getImuAccelerationRange() const
Gets the imuAccelerationRange variable.
Definition: Configuration.cpp:357
rokubimini::Rokubimini::fatalRecoveredCb
void fatalRecoveredCb()
Calls the callbacks in the fatal recovered callbacks list.
Definition: Rokubimini.cpp:111
rokubimini::Rokubimini::postSetupConfiguration
virtual void postSetupConfiguration()=0
Post-setup configuration hook.
rokubimini::Rokubimini::startupWithCommunication
void startupWithCommunication()
Starts up a Rokubimini device after communication has been established.
Definition: Rokubimini.cpp:24
rokubimini::Reading::getWrench
const WrenchType & getWrench() const
Gets the wrench variable.
Definition: Reading.hpp:83
rokubimini::Rokubimini::setForceTorqueFilter
virtual bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)=0
Sets a force torque filter to the device. It's virtual since it's implementation-specific.
rokubimini::configuration::Configuration::hasForceTorqueOffset
bool hasForceTorqueOffset() const
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration ...
Definition: Configuration.cpp:399
rokubimini::Rokubimini::getReading
Reading getReading() const
Gets the reading from the Rokubimini device.
Definition: Rokubimini.cpp:179
rokubimini::Rokubimini::fatalCb
void fatalCb()
Calls the callbacks in the fatal callbacks list.
Definition: Rokubimini.cpp:103
rokubimini::configuration::Configuration::getImuAngularRateFilter
unsigned int getImuAngularRateFilter() const
Gets the imuAccelerationFilter variable.
Definition: Configuration.cpp:345
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
rokubimini::Rokubimini::productName_
std::string productName_
The product name of the rokubimini.
Definition: Rokubimini.hpp:681
rokubimini::configuration::Configuration::load
void load(const std::string &key, const NodeHandlePtr &nh)
Loads the configuration from the parameter server.
Definition: Configuration.cpp:7
rokubimini::Reading
Class representing the readings received from the rokubi mini devices.
Definition: Reading.hpp:35
rokubimini::configuration::Configuration::hasForceTorqueFilter
bool hasForceTorqueFilter() const
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration ...
Definition: Configuration.cpp:393
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
rokubimini::Statusword::isEmpty
bool isEmpty() const
Checks whether the statusword is empty.
Definition: Statusword.cpp:37
rokubimini::Rokubimini::name_
std::string name_
The name of the device.
Definition: Rokubimini.hpp:625
rokubimini::Statusword::getMessagesDiff
void getMessagesDiff(Statusword &previousStatusword, std::vector< std::string > &infos, std::vector< std::string > &warnings, std::vector< std::string > &errors, std::vector< std::string > &fatals) const
Gets the different messages form the previous statusword.
Definition: Statusword.cpp:89
rokubimini::Rokubimini::fatalCbs_
std::multimap< int, FatalCb, std::greater< int > > fatalCbs_
Definition: Rokubimini.hpp:713
rokubimini::configuration::Configuration::getForceTorqueOffset
const Eigen::Matrix< double, 6, 1 > & getForceTorqueOffset() const
Gets the forceTorqueOffset variable.
Definition: Configuration.cpp:261
rokubimini::configuration::Configuration::hasSensorConfiguration
bool hasSensorConfiguration() const
Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuratio...
Definition: Configuration.cpp:387
rokubimini::Rokubimini::deviceDisconnectedCb
void deviceDisconnectedCb()
Calls the callbacks in the device disconnected callbacks list.
Definition: Rokubimini.cpp:126
rokubimini::configuration::Configuration::hasImuAccelerationFilter
bool hasImuAccelerationFilter() const
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configurat...
Definition: Configuration.cpp:429
Rokubimini.hpp
rokubimini::Rokubimini::setSensorCalibration
virtual bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)=0
Sets a sensor calibration to the device. It's virtual since it's implementation-specific.
rokubimini
Tests Configuration.
Definition: ForceTorqueCalibration.hpp:5
rokubimini::configuration::Configuration::hasSensorCalibration
bool hasSensorCalibration() const
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration ...
Definition: Configuration.cpp:417
rokubimini::Rokubimini::statusword_
Statusword statusword_
The current statusword.
Definition: Rokubimini.hpp:641
rokubimini::Rokubimini::deviceDisconnectedCbs_
std::multimap< int, DeviceDisconnectedCb, std::greater< int > > deviceDisconnectedCbs_
Definition: Rokubimini.hpp:729
rokubimini::configuration::Configuration::hasSaveConfiguration
bool hasSaveConfiguration() const
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration ...
Definition: Configuration.cpp:411
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rokubimini::Rokubimini::errorCb
void errorCb()
Calls the callbacks in the error callbacks list.
Definition: Rokubimini.cpp:80
rokubimini::Rokubimini::errorRecoveredCbs_
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
Definition: Rokubimini.hpp:705
rokubimini::Statusword::getStamp
TimePoint getStamp() const
Gets the stamp variable.
Definition: Statusword.cpp:50
rokubimini::Rokubimini::nh_
NodeHandlePtr nh_
The node handle of the ROS node, used by the publishers.
Definition: Rokubimini.hpp:673
rokubimini::Rokubimini::errorCbs_
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
Definition: Rokubimini.hpp:697
rokubimini::configuration::Configuration::getImuAngularRateRange
uint8_t getImuAngularRateRange() const
Gets the imuAngularRateRange variable.
Definition: Configuration.cpp:369
rokubimini::Rokubimini::setStatusword
void setStatusword(Statusword &statusword)
Sets the statusword of the device.
Definition: Rokubimini.cpp:191
rokubimini::configuration::Configuration::getSensorCalibration
const calibration::SensorCalibration & getSensorCalibration() const
Gets the sensorCalibration variable.
Definition: Configuration.cpp:321
ROS_ERROR
#define ROS_ERROR(...)
rokubimini::Rokubimini::NAN_VALUE
static constexpr double NAN_VALUE
NaN abbreviation for convenience.
Definition: Rokubimini.hpp:617
rokubimini::Rokubimini::deviceIsInFatalState
bool deviceIsInFatalState()
Checks if the device is in fatal state.
Definition: Rokubimini.cpp:120
rokubimini::Rokubimini::preSetupConfiguration
virtual void preSetupConfiguration()=0
Pre-setup configuration hook.
rokubimini::configuration::Configuration::getSensorConfiguration
const SensorConfiguration & getSensorConfiguration() const
Gets the sensorConfiguration variable.
Definition: Configuration.cpp:309
rokubimini::Rokubimini::setAngularRateRange
virtual bool setAngularRateRange(const unsigned int range)=0
Sets an angular rate range to the device. It's virtual since it's implementation-specific.
rokubimini::Rokubimini::configuration_
configuration::Configuration configuration_
The Configuration of the device.
Definition: Rokubimini.hpp:633
rokubimini::configuration::Configuration::getSaveConfiguration
bool getSaveConfiguration() const
Gets the saveConfiguration variable.
Definition: Configuration.cpp:285
rokubimini::Rokubimini::readingMutex_
std::recursive_mutex readingMutex_
The mutex for accessing the reading.
Definition: Rokubimini.hpp:657
rokubimini::configuration::Configuration::hasImuAngularRateRange
bool hasImuAngularRateRange() const
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuratio...
Definition: Configuration.cpp:375
rokubimini::Rokubimini::setAccelerationRange
virtual bool setAccelerationRange(const unsigned int range)=0
Sets an acceleration range to the device. It's virtual since it's implementation-specific.
rokubimini::Rokubimini::fatalRecoveredCbs_
std::multimap< int, FatalRecoveredCb, std::greater< int > > fatalRecoveredCbs_
Definition: Rokubimini.hpp:721
rokubimini::Rokubimini::saveConfigParameter
virtual bool saveConfigParameter()=0
Saves the current configuration to the device. It's virtual since it's implementation-specific.
rokubimini::configuration::Configuration::hasImuAngularRateFilter
bool hasImuAngularRateFilter() const
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configurati...
Definition: Configuration.cpp:435
rokubimini::Rokubimini::deviceReconnectedCb
void deviceReconnectedCb()
Calls the callbacks in the device reconnected callbacks list.
Definition: Rokubimini.cpp:170
rokubimini::Statusword
Class representing the different states the communication or the sensors can be in.
Definition: Statusword.hpp:20
rokubimini::Rokubimini::clearGoalStateEnum
void clearGoalStateEnum()
Clears the goal state enumeration.
Definition: Rokubimini.hpp:242
rokubimini::Rokubimini::readingCbs_
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
Definition: Rokubimini.hpp:689
rokubimini::Rokubimini::deviceReconnectedCbs_
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
Definition: Rokubimini.hpp:737
rokubimini::Rokubimini::setSensorConfiguration
virtual bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)=0
Sets a sensor configuration to the device. It's virtual since it's implementation-specific.
ros::Time::now
static Time now()


rokubimini
Author(s):
autogenerated on Sat Apr 15 2023 02:53:52