Segment.cpp
Go to the documentation of this file.
1#include "Segment.h"
2
3#include <SimoxUtility/math/regression/linear.hpp>
4
11
14#include <RobotAPI/libraries/armem_robot_state/aron/Proprioception.aron.generated.h>
18
19#include "SensorValues.h"
20
22{
23
25 Base(memoryToIceAdapter,
26 armem::robot_state::proprioceptionSegmentID.coreSegmentName,
27 arondto::Proprioception::ToAronType(),
28 1024)
29 {
30 }
31
32 Segment::~Segment() = default;
33
34 void
36 {
37 Base::defineProperties(defs, prefix);
38
39 defs->optional(properties.predictionTimeWindow,
40 "prediction.TimeWindow",
41 "Duration of time window into the past to use for predictions"
42 " when requested via the PredictingMemoryInterface (in seconds).");
43 }
44
45 void
47 {
48 Base::init();
49
50 segmentPtr->addPredictor(armem::PredictionEngine{.engineID = "Linear"},
51 [this](const PredictionRequest& request)
52 { return this->predictLinear(request); });
53 }
54
55 void
57 {
58 this->robotUnit = robotUnitPrx;
59
60 std::string providerSegmentName = "Robot";
61
62 KinematicUnitInterfacePrx kinematicUnit = robotUnit->getKinematicUnit();
63 if (kinematicUnit)
64 {
65 providerSegmentName = kinematicUnit->getRobotName();
66 }
67 else
68 {
69 ARMARX_WARNING << "Robot unit '" << robotUnit->ice_getIdentity().name
70 << "' does not have a kinematic unit."
71 << "\n Falling back to provider segment name '" << providerSegmentName
72 << "'.";
73 }
74 this->robotUnitProviderID = segmentPtr->id().withProviderSegmentName(providerSegmentName);
75 }
76
79 DebugObserverHelper* debugObserver) const
80 {
81 return doLocked([this, &timestamp, &debugObserver]()
82 { return getSensorValues(timestamp, debugObserver); });
83 }
84
86 getDictElement(const aron::data::Dict& dict, const std::string& key)
87 {
88 if (dict.hasElement(key))
89 {
91 }
92 return nullptr;
93 }
94
97 {
98 namespace adn = aron::data;
100
101 SensorValuesMap sensorValues;
102 int i = 0;
103
104 Duration tFindData = Duration::MilliSeconds(0),
105 tReadSensorValues = Duration::MilliSeconds(0);
106 TIMING_START(tProcessEntities)
107 segmentPtr->forEachEntity(
108 [&](const wm::Entity& entity)
109 {
110 adn::DictPtr data;
111 {
112 TIMING_START(_tFindData)
113
114 const wm::EntitySnapshot* snapshot =
116 if (not snapshot)
117 {
118 // Got no snapshot <= timestamp. Take latest instead (if present).
119 snapshot = entity.findLatestSnapshot();
120 }
121 if (snapshot)
122 {
123 data = snapshot->findInstanceData();
124 }
125
127 _tFindData, "tFindData " + std::to_string(i), ARMARX_DEBUG);
128 tFindData += Duration::MicroSeconds(_tFindData.toMicroSeconds());
129 }
130 if (data)
131 {
132 TIMING_START(_tReadSensorValues)
133
134 sensorValues.emplace(entity.id().providerSegmentName, readSensorValues(*data));
135
137 _tReadSensorValues, "tReadSensorValues " + std::to_string(i), ARMARX_DEBUG)
138 tReadSensorValues +=
139 Duration::MicroSeconds(_tReadSensorValues.toMicroSeconds());
140 }
141 ++i;
142 });
143 TIMING_END_STREAM(tProcessEntities, ARMARX_DEBUG)
144
145 if (debugObserver)
146 {
147 debugObserver->setDebugObserverDatafield(dp + "t 1.1 Process Entities (ms)",
148 tProcessEntities.toMilliSecondsDouble());
149 debugObserver->setDebugObserverDatafield(dp + "t 1.1.1 FindData (ms)",
150 tFindData.toMilliSecondsDouble());
151 debugObserver->setDebugObserverDatafield(dp + "t 1.1.2 ReadSensorValues (ms)",
152 tReadSensorValues.toMilliSecondsDouble());
153 }
154
155 return sensorValues;
156 }
157
158 const armem::MemoryID&
160 {
161 return robotUnitProviderID;
162 }
163
164 Eigen::VectorXd
166 {
167 namespace adn = aron::data;
168
169 std::vector<double> values;
170
171 auto addData = [&](adn::DictPtr dict) // NOLINT
172 {
173 for (const auto& [name, value] : dict->getElements())
174 {
175 values.push_back(
176 static_cast<double>(adn::Float::DynamicCastAndCheck(value)->getValue()));
177 }
178 };
179
180 if (adn::DictPtr joints = getDictElement(data, "joints"))
181 {
182 if (adn::DictPtr jointsPosition = getDictElement(*joints, "position"))
183 {
184 addData(jointsPosition);
185 }
186 if (adn::DictPtr jointsVelocity = getDictElement(*joints, "velocity"))
187 {
188 addData(jointsVelocity);
189 }
190 if (adn::DictPtr jointsTorque = getDictElement(*joints, "torque"))
191 {
192 addData(jointsTorque);
193 }
194 }
195 Eigen::VectorXd vec =
196 Eigen::Map<Eigen::VectorXd>(values.data(), static_cast<Eigen::Index>(values.size()));
197 return vec;
198 }
199
200 void
201 emplaceJointData(const Eigen::VectorXd& jointData, arondto::Proprioception& dataTemplate)
202 {
203 Eigen::Index row = 0;
204 for (auto& [joint, value] : dataTemplate.joints.position)
205 {
206 value = static_cast<float>(jointData(row++));
207 }
208 for (auto& [joint, value] : dataTemplate.joints.velocity)
209 {
210 value = static_cast<float>(jointData(row++));
211 }
212 for (auto& [joint, value] : dataTemplate.joints.torque)
213 {
214 value = static_cast<float>(jointData(row++));
215 }
216 }
217
220 {
221 PredictionResult result;
222 result.snapshotID = request.snapshotID;
223 if (request.predictionSettings.predictionEngineID != "Linear")
224 {
225 result.success = false;
226 result.errorMessage = "Prediction engine " +
228 " is not supported in Proprioception.";
229 return result;
230 }
231
232 const DateTime timeOrigin = DateTime::Now();
233 const armarx::Duration timeWindow =
234 Duration::SecondsDouble(properties.predictionTimeWindow);
236
237 doLocked(
238 // Default capture because the number of variables was getting out of hand
239 [&, this]()
240 {
242 Eigen::VectorXd,
245 request.snapshotID,
246 timeOrigin - timeWindow,
247 timeOrigin,
248 [](const aron::data::DictPtr& data) { return readJointData(*data); },
249 [](const aron::data::DictPtr& data) { return data; });
250 });
251
252 if (info.success)
253 {
254 Eigen::VectorXd latestJoints = readJointData(*info.latestValue);
255 Eigen::VectorXd prediction(latestJoints.size());
256 if (info.timestampsSec.size() <= 1)
257 {
258 prediction = latestJoints;
259 }
260 else
261 {
262 using simox::math::LinearRegression;
263 const bool inputOffset = false;
264 const LinearRegression model = LinearRegression<Eigen::Dynamic>::Fit(
265 info.timestampsSec, info.values, inputOffset);
266 const auto predictionTime = request.snapshotID.timestamp;
267 prediction = model.predict((predictionTime - timeOrigin).toSecondsDouble());
268 }
269
270 arondto::Proprioception templateData =
271 arondto::Proprioception::FromAron(info.latestValue);
272 emplaceJointData(prediction, templateData);
273 result.success = true;
274 result.prediction = templateData.toAron();
275 }
276 else
277 {
278 result.success = false;
279 result.errorMessage = info.errorMessage;
280 }
281
282 return result;
283 }
284
286 Segment::readSensorValues(const wm::EntityInstanceData& data)
287 {
288 namespace adn = aron::data;
289
290 // Just get what we need without casting the whole data.
291 SensorValues sensorValues;
292 auto checkJVM = [&sensorValues](const std::string& name)
293 {
294 if (sensorValues.jointValueMap.find(name) == sensorValues.jointValueMap.end())
295 {
296 sensorValues.jointValueMap[name] = JointValues();
297 }
298 };
299 if (adn::DictPtr joints = getDictElement(data, "joints"))
300 {
301 if (adn::DictPtr values = getDictElement(*joints, "position"))
302 {
303 for (const auto& [name, value] : values->getElements())
304 {
305 checkJVM(name);
306 sensorValues.jointValueMap[name].position =
307 adn::Float::DynamicCastAndCheck(value)->getValue();
308 }
309 }
310 if (adn::DictPtr values = getDictElement(*joints, "velocity"))
311 {
312 for (const auto& [name, value] : values->getElements())
313 {
314 checkJVM(name);
315 sensorValues.jointValueMap[name].velocity =
316 adn::Float::DynamicCastAndCheck(value)->getValue();
317 }
318 }
319 if (adn::DictPtr values = getDictElement(*joints, "torque"))
320 {
321 for (const auto& [name, value] : values->getElements())
322 {
323 checkJVM(name);
324 sensorValues.jointValueMap[name].torque =
325 adn::Float::DynamicCastAndCheck(value)->getValue();
326 }
327 }
328 }
329 if (adn::DictPtr forceTorqueMap = getDictElement(data, "forceTorque"))
330 {
331 for (const auto& [name, value] : forceTorqueMap->getElements())
332 {
333 if (adn::DictPtr forceTorqueValues = aron::data::Dict::DynamicCastAndCheck(value))
334 {
335 const Eigen::Vector3f torque =
337 adn::NDArray::DynamicCastAndCheck(
338 forceTorqueValues->getElement("torque")));
339
340 const Eigen::Vector3f force =
342 adn::NDArray::DynamicCastAndCheck(
343 forceTorqueValues->getElement("force")));
344
345 sensorValues.forceTorqueValuesMap[name] =
346 ForceTorqueValues{.force = force, .torque = torque};
347 }
348 }
349 }
350 return sensorValues;
351 }
352
353} // namespace armarx::armem::server::robot_state::proprioception
std::string timestamp()
uint8_t data[1]
static DateTime Now()
Definition DateTime.cpp:51
Brief description of class DebugObserverHelper.
void setDebugObserverDatafield(const std::string &channelName, const std::string &datafieldName, const TimedVariantPtr &value) const
std::string providerSegmentName
Definition MemoryID.h:52
EntitySnapshotT * findLatestSnapshot()
Return the snapshot with the most recent timestamp.
Definition EntityBase.h:229
const EntitySnapshotT * findLatestSnapshotBeforeOrAt(const Time &time) const
Return the latest snapshot before or at time.
Definition EntityBase.h:320
Helps connecting a Memory server to the Ice interface.
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
Definition Segment.cpp:35
void onConnect(RobotUnitInterfacePrx robotUnitPrx)
Definition Segment.cpp:56
SensorValuesMap getSensorValues(const armem::Time &timestamp, DebugObserverHelper *debugObserver=nullptr) const
Definition Segment.cpp:96
SensorValuesMap getSensorValuesLocking(const armem::Time &timestamp, DebugObserverHelper *debugObserver=nullptr) const
Definition Segment.cpp:78
Segment(server::MemoryToIceAdapter &iceMemory)
Definition Segment.cpp:24
armem::PredictionResult predictLinear(const armem::PredictionRequest &request) const
Definition Segment.cpp:219
virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
auto doLocked(FunctionT &&function) const
Execute function under shared (read) lock.
std::map< std::string, VariantPtr > getElements() const
Definition Dict.cpp:250
bool hasElement(const std::string &) const
Definition Dict.cpp:228
VariantPtr getElement(const std::string &) const
Definition Dict.cpp:234
static Eigen::Vector3f ConvertToVector3f(const data::NDArrayPtr &)
Represents a point in time.
Definition DateTime.h:25
Represents a duration.
Definition Duration.h:17
static Duration MicroSeconds(std::int64_t microSeconds)
Constructs a duration in microseconds.
Definition Duration.cpp:24
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
Definition Duration.cpp:78
double toMilliSecondsDouble() const
Returns the amount of milliseconds.
Definition Duration.cpp:66
static Duration MilliSeconds(std::int64_t milliSeconds)
Constructs a duration in milliseconds.
Definition Duration.cpp:48
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
#define TIMING_START(name)
Helper macro to do timing tests.
Definition TimeUtil.h:289
#define TIMING_END_COMMENT_STREAM(name, comment, os)
Prints duration with comment in front of it, yet only once per second.
Definition TimeUtil.h:293
#define TIMING_END_STREAM(name, os)
Prints duration.
Definition TimeUtil.h:310
std::unordered_map< std::string, SensorValues > SensorValuesMap
void emplaceJointData(const Eigen::VectorXd &jointData, arondto::Proprioception &dataTemplate)
Definition Segment.cpp:201
Eigen::VectorXd readJointData(const wm::EntityInstanceData &data)
Definition Segment.cpp:165
armem::wm::EntitySnapshot EntitySnapshot
armarx::aron::data::Dict EntityInstanceData
SnapshotRangeInfo< DataType, LatestType > getSnapshotsInRange(const SegmentType *segment, const MemoryID &entityID, const DateTime &startTime, const DateTime &endTime, std::function< DataType(const aron::data::DictPtr &)> dictToData, std::function< LatestType(const aron::data::DictPtr &)> dictToLatest)
Get data points for the snapshots of an entity in a given time range.
armarx::core::time::DateTime Time
armarx::core::time::Duration Duration
A convenience header to include all aron files (full include, not forward declared)
std::shared_ptr< Dict > DictPtr
Definition Dict.h:42
::IceInternal::ProxyHandle<::IceProxy::armarx::RobotUnitInterface > RobotUnitInterfacePrx
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
PredictionSettings predictionSettings
Definition Prediction.h:51
aron::data::DictPtr prediction
Definition Prediction.h:63
Holds info on snapshot data extracted from a time range.
aron::data::DictPtr findInstanceData(int instanceIndex=0) const