Rokubimini.cpp
Go to the documentation of this file.
1 // std
2 #include <chrono>
3 
4 // rokubimini
6 namespace rokubimini
7 {
8 bool Rokubimini::loadRokubiminiSetup(const std::shared_ptr<rokubimini::setup::Rokubimini> setup)
9 {
10  name_ = setup->name_;
11  configuration_ = setup->configuration_;
12  return true;
13 }
14 
16 {
18  {
20  }
22  {
24  }
26  {
28  }
30  {
32  }
34  {
36  }
38  {
40  }
42  {
44  }
45 
47  {
49  }
50 
52  {
54  {
56  }
57  }
59 }
60 
62 {
63 }
64 
66 {
67  // stateMachine_.clearGoalStateEnum();
68 }
69 
71 {
72  for (const auto& error_cb : errorCbs_)
73  {
74  error_cb.second(getName());
75  }
76 }
77 
79 {
81  for (const auto& error_recovered_cb : errorRecoveredCbs_)
82  {
83  error_recovered_cb.second(getName());
84  }
85 }
86 
88 {
89  return true;
90  // return getStatusword().getStateEnum() == fsm::StateEnum::Error;
91 }
92 
94 {
95  for (const auto& fatal_cb : fatalCbs_)
96  {
97  fatal_cb.second(getName());
98  }
99 }
100 
102 {
104  for (const auto& fatal_recovered_cb : fatalRecoveredCbs_)
105  {
106  fatal_recovered_cb.second(getName());
107  }
108 }
109 
111 {
112  return true;
113  // return getStatusword().getStateEnum() == fsm::StateEnum::Fatal;
114 }
115 
117 {
118  statuswordRequested_ = false;
120  for (const auto& device_disconnected_cb : deviceDisconnectedCbs_)
121  {
122  device_disconnected_cb.second(getName());
123  }
124 
125  // Set statusword and reading accordingly.
126  // statusword_.resetData();
127  Reading reading;
128  const auto& stamp = ros::Time::now();
129  {
130  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
131  reading_.getWrench().header.stamp = stamp;
132  reading_.getImu().header.stamp = stamp;
134  if (getConfiguration().getSetReadingToNanOnDisconnect())
135  {
136  reading_.getWrench().wrench.force.x = NAN_VALUE;
137  reading_.getWrench().wrench.force.y = NAN_VALUE;
138  reading_.getWrench().wrench.force.z = NAN_VALUE;
139  reading_.getWrench().wrench.torque.x = NAN_VALUE;
140  reading_.getWrench().wrench.torque.y = NAN_VALUE;
141  reading_.getWrench().wrench.torque.z = NAN_VALUE;
142 
143  reading_.getImu().angular_velocity.x = NAN_VALUE;
144  reading_.getImu().angular_velocity.y = NAN_VALUE;
145  reading_.getImu().angular_velocity.z = NAN_VALUE;
146  reading_.getImu().linear_acceleration.x = NAN_VALUE;
147  reading_.getImu().linear_acceleration.y = NAN_VALUE;
148  reading_.getImu().linear_acceleration.z = NAN_VALUE;
149  }
150  reading = reading_;
151  }
152 
153  // External reading callbacks.
154  for (const auto& reading_cb : readingCbs_)
155  {
156  reading_cb.second(getName(), reading);
157  }
158 }
159 
161 {
162  // setGoalStateEnum(getConfiguration().getGoalStateEnumStartup());
163  for (const auto& device_reconnected_cb : deviceReconnectedCbs_)
164  {
165  device_reconnected_cb.second(getName());
166  }
167 }
168 
170 {
171  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
172  return reading_;
173 }
174 
175 void Rokubimini::getReading(Reading& reading) const
176 {
177  std::lock_guard<std::recursive_mutex> lock(readingMutex_);
178  reading = reading_;
179 }
180 
182 {
183  // If the stamp has not changed, we assume it is again the same statusword.
184  if (statusword.getStamp() == statusword_.getStamp())
185  {
186  return;
187  }
188 
189  // Check if statusword contains new data.
190  if (statusword_.isEmpty() || statusword.getData() != statusword_.getData())
191  {
192  ROS_DEBUG_STREAM("Received new statusword (" << statusword << ").");
193  std::vector<std::string> infos;
194  std::vector<std::string> warnings;
195  std::vector<std::string> errors;
196  std::vector<std::string> fatals;
197  statusword.getMessagesDiff(statusword_, infos, warnings, errors, fatals);
198  for (const std::string& info : infos)
199  {
200  ROS_INFO_STREAM("[" << name_.c_str() << "] " << info);
201  }
202  for (const std::string& warning : warnings)
203  {
204  ROS_WARN_STREAM("[" << name_.c_str() << "] " << warning);
205  }
206  for (const std::string& error : errors)
207  {
208  ROS_ERROR_STREAM("[" << name_.c_str() << "] " << error);
209  }
210  for (const std::string& fatal : fatals)
211  {
212  ROS_ERROR_STREAM("[" << name_.c_str() << "] " << fatal);
213  }
214  }
215 
216  // Always update statusword to set new time stamp.
217  statusword_ = statusword;
218 }
219 
220 } // namespace rokubimini
bool hasForceTorqueOffset() const
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration ...
bool hasImuAccelerationRange() const
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configurati...
bool deviceIsInErrorState()
Checks if the device is in error state.
Definition: Rokubimini.cpp:87
bool hasForceTorqueFilter() const
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration ...
bool hasSensorCalibration() const
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration ...
const WrenchType & getWrench() const
Gets the wrench variable.
Definition: Reading.hpp:83
std::multimap< int, FatalRecoveredCb, std::greater< int > > fatalRecoveredCbs_
Definition: Rokubimini.hpp:660
virtual bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)=0
Sets a sensor calibration to the device. It&#39;s virtual since it&#39;s implementation-specific.
void deviceDisconnectedCb()
Calls the callbacks in the device disconnected callbacks list.
Definition: Rokubimini.cpp:116
Statusword statusword_
The current statusword.
Definition: Rokubimini.hpp:588
const ForceTorqueFilter & getForceTorqueFilter() const
Gets the forceTorqueFilter variable.
bool deviceIsInFatalState()
Checks if the device is in fatal state.
Definition: Rokubimini.cpp:110
void setStatusword(Statusword &statusword)
Sets the statusword of the device.
Definition: Rokubimini.cpp:181
static constexpr double NAN_VALUE
NaN abbreviation for convenience.
Definition: Rokubimini.hpp:564
virtual bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)=0
Sets a force torque filter to the device. It&#39;s virtual since it&#39;s implementation-specific.
void errorRecoveredCb()
Calls the callbacks in the error recovered callbacks list.
Definition: Rokubimini.cpp:78
bool loadRokubiminiSetup(std::shared_ptr< rokubimini::setup::Rokubimini > setup)
Loads the configuration of the device from the {Rokubimini Setup} provided.
Definition: Rokubimini.cpp:8
bool hasImuAngularRateFilter() const
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configurati...
virtual bool setAccelerationRange(const unsigned int range)=0
Sets an acceleration range to the device. It&#39;s virtual since it&#39;s implementation-specific.
std::multimap< int, FatalCb, std::greater< int > > fatalCbs_
Definition: Rokubimini.hpp:652
virtual bool setAngularRateRange(const unsigned int range)=0
Sets an angular rate range to the device. It&#39;s virtual since it&#39;s implementation-specific.
bool hasSensorConfiguration() const
Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuratio...
Class representing the readings received from the rokubi mini devices.
Definition: Reading.hpp:35
void clearGoalStateEnum()
Clears the goal state enumeration.
Definition: Rokubimini.hpp:239
const Eigen::Matrix< double, 6, 1 > & getForceTorqueOffset() const
Gets the forceTorqueOffset variable.
Class representing the different states the communication or the sensors can be in.
Definition: Statusword.hpp:20
void startupWithoutCommunication()
Starts up a Rokubimini device before communication has been established by the BusManager.
Definition: Rokubimini.cpp:61
bool hasImuAngularRateRange() const
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuratio...
bool isEmpty() const
Checks whether the statusword is empty.
Definition: Statusword.cpp:37
bool getUseCustomCalibration() const
Gets the useCustomCalibration variable.
uint32_t getData() const
Gets the data variable.
Definition: Statusword.cpp:63
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
bool getSaveConfiguration() const
Gets the saveConfiguration variable.
unsigned int getImuAngularRateFilter() const
Gets the imuAccelerationFilter variable.
std::string getName() const
Gets the name of the device.
Definition: Rokubimini.hpp:57
bool hasSaveConfiguration() const
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration ...
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
Definition: Rokubimini.hpp:676
uint8_t getImuAccelerationRange() const
Gets the imuAccelerationRange variable.
configuration::Configuration configuration_
The Configuration of the device.
Definition: Rokubimini.hpp:580
void deviceReconnectedCb()
Calls the callbacks in the device reconnected callbacks list.
Definition: Rokubimini.cpp:160
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
Definition: Reading.hpp:143
const calibration::SensorCalibration & getSensorCalibration() const
Gets the sensorCalibration variable.
unsigned int getImuAccelerationFilter() const
uint8_t getImuAngularRateRange() const
Gets the imuAngularRateRange variable.
TimePoint getStamp() const
Gets the stamp variable.
Definition: Statusword.cpp:50
void errorCb()
Calls the callbacks in the error callbacks list.
Definition: Rokubimini.cpp:70
std::atomic< bool > statuswordRequested_
Flag indicating if a statusword has been actively requested.
Definition: Rokubimini.hpp:596
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
Definition: Rokubimini.hpp:636
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
std::multimap< int, DeviceDisconnectedCb, std::greater< int > > deviceDisconnectedCbs_
Definition: Rokubimini.hpp:668
void fatalCb()
Calls the callbacks in the fatal callbacks list.
Definition: Rokubimini.cpp:93
Reading reading_
The reading of the device.
Definition: Rokubimini.hpp:612
Reading getReading() const
Gets the reading from the Rokubimini device.
Definition: Rokubimini.cpp:169
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
Definition: Rokubimini.hpp:644
#define ROS_INFO_STREAM(args)
virtual bool setAccelerationFilter(const unsigned int filter)=0
Sets an acceleration filter to the device. It&#39;s virtual since it&#39;s implementation-specific.
bool hasImuAccelerationFilter() const
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configurat...
void fatalRecoveredCb()
Calls the callbacks in the fatal recovered callbacks list.
Definition: Rokubimini.cpp:101
void startupWithCommunication()
Starts up a Rokubimini device after communication has been established.
Definition: Rokubimini.cpp:15
virtual void doStartupWithCommunication()=0
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
Definition: Rokubimini.hpp:628
static Time now()
virtual bool setAngularRateFilter(const unsigned int filter)=0
Sets an angular rate filter to the device. It&#39;s virtual since it&#39;s implementation-specific.
virtual bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)=0
Sets a force torque offset to the device. It&#39;s virtual since it&#39;s implementation-specific.
#define ROS_ERROR_STREAM(args)
const SensorConfiguration & getSensorConfiguration() const
Gets the sensorConfiguration variable.
configuration::Configuration & getConfiguration()
Non-const version of getConfiguration() const. Gets the Configuration of the device.
Definition: Rokubimini.hpp:69
std::string name_
The name of the device.
Definition: Rokubimini.hpp:572
virtual bool saveConfigParameter()=0
Saves the current configuration to the device. It&#39;s virtual since it&#39;s implementation-specific.
std::recursive_mutex readingMutex_
The mutex for accessing the reading.
Definition: Rokubimini.hpp:604
const ImuType & getImu() const
Gets the imu variable.
Definition: Reading.hpp:58
virtual bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)=0
Sets a sensor configuration to the device. It&#39;s virtual since it&#39;s implementation-specific.
Tests Configuration.


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