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 
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 
85  static aron::data::DictPtr
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)
108  [&](const wm::Entity& entity)
109  {
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,
244  segmentPtr,
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].velocity =
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  {
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
armarx::armem::MemoryID::timestamp
Time timestamp
Definition: MemoryID.h:54
TIMING_START
#define TIMING_START(name)
Definition: TimeUtil.h:289
armarx::armem::PredictionRequest
Definition: Prediction.h:48
armarx::armem::PredictionResult::snapshotID
armem::MemoryID snapshotID
Definition: Prediction.h:62
armarx::armem::PredictionEngine::engineID
std::string engineID
Definition: Prediction.h:34
armarx::armem::SnapshotRangeInfo::timestampsSec
std::vector< double > timestampsSec
Definition: prediction_helpers.h:45
armarx::armem::server::robot_state::proprioception::Segment::getSensorValues
SensorValuesMap getSensorValues(const armem::Time &timestamp, DebugObserverHelper *debugObserver=nullptr) const
Definition: Segment.cpp:96
prediction_helpers.h
armarx::armem::MemoryID::providerSegmentName
std::string providerSegmentName
Definition: MemoryID.h:52
armarx::armem::server::robot_state::proprioception::readJointData
Eigen::VectorXd readJointData(const wm::EntityInstanceData &data)
Definition: Segment.cpp:165
armarx::armem::server::MemoryToIceAdapter
Helps connecting a Memory server to the Ice interface.
Definition: MemoryToIceAdapter.h:19
armarx::core::time::DateTime::Now
static DateTime Now()
Definition: DateTime.cpp:51
MemoryID.h
ARMARX_CHECK_NOT_NULL
#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...
Definition: ExpressionException.h:206
armarx::armem::PredictionRequest::predictionSettings
PredictionSettings predictionSettings
Definition: Prediction.h:51
armarx::aron::data::Dict::getElement
VariantPtr getElement(const std::string &) const
Definition: Dict.cpp:234
armarx::armem::server::robot_state::proprioception
Definition: forward_declarations.h:78
armarx::armem
Definition: LegacyRobotStateMemoryAdapter.cpp:32
ProsthesisInterface.values
values
Definition: ProsthesisInterface.py:190
armarx::armem::server::robot_state::proprioception::Segment::init
void init() override
Definition: Segment.cpp:46
armarx::armem::server::robot_state::proprioception::SensorValues::jointValueMap
JointValuesMap jointValueMap
Definition: SensorValues.h:45
armarx::core::time::Duration::toMilliSecondsDouble
double toMilliSecondsDouble() const
Returns the amount of milliseconds.
Definition: Duration.cpp:66
armarx::armem::server::robot_state::proprioception::emplaceJointData
void emplaceJointData(const Eigen::VectorXd &jointData, arondto::Proprioception &dataTemplate)
Definition: Segment.cpp:201
armarx::armem::server::robot_state::proprioception::SensorValues
Definition: SensorValues.h:43
armarx::aron::data::detail::SpecializedVariantBase< data::dto::Dict, Dict >::DynamicCastAndCheck
static PointerType DynamicCastAndCheck(const VariantPtr &n)
Definition: SpecializedVariant.h:134
armarx::armem::PredictionResult
Definition: Prediction.h:57
armarx::armem::server::wm::Entity
Definition: memory_definitions.h:27
armarx::armem::server::robot_state::proprioception::JointValues
Definition: SensorValues.h:29
armarx::armem::base::detail::ForEachEntityMixin::forEachEntity
bool forEachEntity(FunctionT &&func)
Definition: iteration_mixins.h:259
TIMING_END_STREAM
#define TIMING_END_STREAM(name, os)
Definition: TimeUtil.h:310
armarx::armem::server::robot_state::proprioception::Segment::predictLinear
armem::PredictionResult predictLinear(const armem::PredictionRequest &request) const
Definition: Segment.cpp:219
armarx::armem::SnapshotRangeInfo::success
bool success
Definition: prediction_helpers.h:42
ObserverObjectFactories.h
armarx::armem::server::segment::detail::SegmentBase< server::wm::CoreSegment >::segmentPtr
server::wm::CoreSegment * segmentPtr
Definition: SpecializedSegment.h:53
armarx::armem::MemoryID::withProviderSegmentName
MemoryID withProviderSegmentName(const std::string &name) const
Definition: MemoryID.cpp:417
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:855
armarx::armem::MemoryID
A memory ID.
Definition: MemoryID.h:47
armarx::armem::PredictionResult::prediction
aron::data::DictPtr prediction
Definition: Prediction.h:63
armarx::armem::base::EntityBase::findLatestSnapshot
EntitySnapshotT * findLatestSnapshot()
Return the snapshot with the most recent timestamp.
Definition: EntityBase.h:228
armarx::armem::server::segment::detail::SegmentBase< server::wm::CoreSegment >
armarx::armem::server::segment::SpecializedCoreSegment::init
virtual void init() override
Definition: SpecializedCoreSegment.cpp:47
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:184
armarx::armem::server::segment::SpecializedCoreSegment::doLocked
auto doLocked(FunctionT &&function) const
Definition: SpecializedCoreSegment.h:38
armarx::core::time::Duration::SecondsDouble
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
Definition: Duration.cpp:78
All.h
armarx::armem::SnapshotRangeInfo::latestValue
LatestType latestValue
Definition: prediction_helpers.h:47
armarx::aron::data::Dict::hasElement
bool hasElement(const std::string &) const
Definition: Dict.cpp:228
timestamp
std::string timestamp()
Definition: CartographerAdapter.cpp:85
armarx::armem::server::robot_state::proprioception::Segment::getRobotUnitProviderID
const armem::MemoryID & getRobotUnitProviderID() const
Definition: Segment.cpp:159
EigenConverter.h
armarx::armem::getSnapshotsInRange
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.
Definition: prediction_helpers.h:72
armarx::armem::wm::EntitySnapshot
Client-side working memory entity snapshot.
Definition: memory_definitions.h:80
armarx::armem::SnapshotRangeInfo::values
std::vector< DataType > values
Definition: prediction_helpers.h:46
armarx::armem::base::detail::MemoryItem::id
MemoryID & id()
Definition: MemoryItem.h:25
armarx::armem::server::wm::detail::Prediction::addPredictor
void addPredictor(const PredictionEngine &engine, Predictor &&predictor)
Definition: Prediction.h:68
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:41
armarx::armem::server::robot_state::proprioception::SensorValuesMap
std::unordered_map< std::string, SensorValues > SensorValuesMap
Definition: forward_declarations.h:85
armarx::armem::PredictionEngine
Definition: Prediction.h:32
TIMING_END_COMMENT_STREAM
#define TIMING_END_COMMENT_STREAM(name, comment, os)
Definition: TimeUtil.h:293
ExpressionException.h
armarx::armem::server::wm::CoreSegment
base::CoreSegmentBase
Definition: memory_definitions.h:75
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::aron::data::DictPtr
std::shared_ptr< Dict > DictPtr
Definition: Dict.h:41
DebugObserverHelper.h
Segment.h
armarx::armem::PredictionResult::errorMessage
std::string errorMessage
Definition: Prediction.h:60
TimeUtil.h
armarx::armem::robot_state::proprioceptionSegmentID
const MemoryID proprioceptionSegmentID
Definition: memory_ids.cpp:31
armarx::DebugObserverHelper::setDebugObserverDatafield
void setDebugObserverDatafield(const std::string &channelName, const std::string &datafieldName, const TimedVariantPtr &value) const
Definition: DebugObserverHelper.cpp:83
armarx::aron::data::Dict::getElements
std::map< std::string, VariantPtr > getElements() const
Definition: Dict.cpp:250
PropertyDefinitionContainer.h
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::core::time::Duration
Represents a duration.
Definition: Duration.h:16
IceInternal::ProxyHandle<::IceProxy::armarx::RobotUnitInterface >
armarx::armem::base::EntityBase::findLatestSnapshotBeforeOrAt
const EntitySnapshotT * findLatestSnapshotBeforeOrAt(const Time &time) const
Return the latest snapshot before or at time.
Definition: EntityBase.h:319
armarx::armem::SnapshotRangeInfo::errorMessage
std::string errorMessage
Definition: prediction_helpers.h:43
armarx::armem::server::robot_state::proprioception::Segment::~Segment
virtual ~Segment() override
armarx::armem::SnapshotRangeInfo
Holds info on snapshot data extracted from a time range.
Definition: prediction_helpers.h:40
armarx::armem::server::robot_state::proprioception::Segment::onConnect
void onConnect(RobotUnitInterfacePrx robotUnitPrx)
Definition: Segment.cpp:56
armarx::armem::server::robot_state::proprioception::Segment::getSensorValuesLocking
SensorValuesMap getSensorValuesLocking(const armem::Time &timestamp, DebugObserverHelper *debugObserver=nullptr) const
Definition: Segment.cpp:78
armarx::armem::server::robot_state::proprioception::SensorValues::forceTorqueValuesMap
ForceTorqueValuesMap forceTorqueValuesMap
Definition: SensorValues.h:46
armarx::armem::server::robot_state::proprioception::Segment::Segment
Segment(server::MemoryToIceAdapter &iceMemory)
Definition: Segment.cpp:24
Logging.h
armarx::armem::PredictionResult::success
bool success
Definition: Prediction.h:59
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:193
armarx::core::time::Duration::MicroSeconds
static Duration MicroSeconds(std::int64_t microSeconds)
Constructs a duration in microseconds.
Definition: Duration.cpp:24
armarx::DebugObserverHelper
Brief description of class DebugObserverHelper.
Definition: DebugObserverHelper.h:51
armarx::armem::PredictionRequest::snapshotID
armem::MemoryID snapshotID
Definition: Prediction.h:50
armarx::armem::server::segment::SpecializedCoreSegment::defineProperties
virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
Definition: SpecializedCoreSegment.cpp:31
memory_ids.h
SensorValues.h
armarx::core::time::Duration::MilliSeconds
static Duration MilliSeconds(std::int64_t milliSeconds)
Constructs a duration in milliseconds.
Definition: Duration.cpp:48
armarx::aron::data::Dict
Definition: Dict.h:44
armarx::aron::data::converter::AronEigenConverter::ConvertToVector3f
static Eigen::Vector3f ConvertToVector3f(const data::NDArrayPtr &)
Definition: EigenConverter.cpp:45
armarx::armem::PredictionSettings::predictionEngineID
std::string predictionEngineID
Definition: Prediction.h:42
armarx::armem::server::robot_state::proprioception::Segment::defineProperties
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
Definition: Segment.cpp:35