Go to the documentation of this file.
3 #include <SimoxUtility/math/regression/linear.hpp>
14 #include <RobotAPI/libraries/armem_robot_state/aron/Proprioception.aron.generated.h>
25 Base(memoryToIceAdapter,
27 arondto::Proprioception::ToAronType(),
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).");
58 this->robotUnit = robotUnitPrx;
60 std::string providerSegmentName =
"Robot";
62 KinematicUnitInterfacePrx kinematicUnit = robotUnit->getKinematicUnit();
65 providerSegmentName = kinematicUnit->getRobotName();
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
123 data = snapshot->findInstanceData();
148 tProcessEntities.toMilliSecondsDouble());
152 tReadSensorValues.toMilliSecondsDouble());
161 return robotUnitProviderID;
169 std::vector<double>
values;
176 static_cast<double>(adn::Float::DynamicCastAndCheck(
value)->getValue()));
182 if (
adn::DictPtr jointsPosition = getDictElement(*joints,
"position"))
184 addData(jointsPosition);
186 if (
adn::DictPtr jointsVelocity = getDictElement(*joints,
"velocity"))
188 addData(jointsVelocity);
190 if (
adn::DictPtr jointsTorque = getDictElement(*joints,
"torque"))
192 addData(jointsTorque);
195 Eigen::VectorXd vec =
196 Eigen::Map<Eigen::VectorXd>(
values.data(),
static_cast<Eigen::Index
>(
values.size()));
203 Eigen::Index row = 0;
204 for (
auto& [joint,
value] : dataTemplate.joints.position)
206 value =
static_cast<float>(jointData(row++));
208 for (
auto& [joint,
value] : dataTemplate.joints.velocity)
210 value =
static_cast<float>(jointData(row++));
212 for (
auto& [joint,
value] : dataTemplate.joints.torque)
214 value =
static_cast<float>(jointData(row++));
228 " is not supported in Proprioception.";
246 timeOrigin - timeWindow,
255 Eigen::VectorXd prediction(latestJoints.size());
258 prediction = latestJoints;
262 using simox::math::LinearRegression;
263 const bool inputOffset =
false;
264 const LinearRegression model = LinearRegression<Eigen::Dynamic>::Fit(
267 prediction = model.predict((predictionTime - timeOrigin).toSecondsDouble());
270 arondto::Proprioception templateData =
271 arondto::Proprioception::FromAron(info.
latestValue);
292 auto checkJVM = [&sensorValues](
const std::string& name)
303 for (
const auto& [name,
value] :
values->getElements())
307 adn::Float::DynamicCastAndCheck(
value)->getValue();
312 for (
const auto& [name,
value] :
values->getElements())
316 adn::Float::DynamicCastAndCheck(
value)->getValue();
321 for (
const auto& [name,
value] :
values->getElements())
325 adn::Float::DynamicCastAndCheck(
value)->getValue();
331 for (
const auto& [name,
value] : forceTorqueMap->getElements())
335 const Eigen::Vector3f torque =
337 adn::NDArray::DynamicCastAndCheck(
338 forceTorqueValues->getElement(
"torque")));
340 const Eigen::Vector3f force =
342 adn::NDArray::DynamicCastAndCheck(
343 forceTorqueValues->getElement(
"force")));
346 ForceTorqueValues{.force = force, .torque = torque};
#define TIMING_START(name)
armem::MemoryID snapshotID
std::vector< double > timestampsSec
SensorValuesMap getSensorValues(const armem::Time ×tamp, DebugObserverHelper *debugObserver=nullptr) const
std::string providerSegmentName
Eigen::VectorXd readJointData(const wm::EntityInstanceData &data)
Helps connecting a Memory server to the Ice interface.
#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...
PredictionSettings predictionSettings
VariantPtr getElement(const std::string &) const
JointValuesMap jointValueMap
double toMilliSecondsDouble() const
Returns the amount of milliseconds.
void emplaceJointData(const Eigen::VectorXd &jointData, arondto::Proprioception &dataTemplate)
static PointerType DynamicCastAndCheck(const VariantPtr &n)
bool forEachEntity(FunctionT &&func)
#define TIMING_END_STREAM(name, os)
armem::PredictionResult predictLinear(const armem::PredictionRequest &request) const
server::wm::CoreSegment * segmentPtr
MemoryID withProviderSegmentName(const std::string &name) const
std::shared_ptr< Value > value()
aron::data::DictPtr prediction
EntitySnapshotT * findLatestSnapshot()
Return the snapshot with the most recent timestamp.
virtual void init() override
auto doLocked(FunctionT &&function) const
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
bool hasElement(const std::string &) const
const armem::MemoryID & getRobotUnitProviderID() const
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.
Client-side working memory entity snapshot.
std::vector< DataType > values
void addPredictor(const PredictionEngine &engine, Predictor &&predictor)
const std::string & to_string(const std::string &s)
std::unordered_map< std::string, SensorValues > SensorValuesMap
#define TIMING_END_COMMENT_STREAM(name, comment, os)
Represents a point in time.
std::shared_ptr< Dict > DictPtr
const MemoryID proprioceptionSegmentID
void setDebugObserverDatafield(const std::string &channelName, const std::string &datafieldName, const TimedVariantPtr &value) const
std::map< std::string, VariantPtr > getElements() const
const EntitySnapshotT * findLatestSnapshotBeforeOrAt(const Time &time) const
Return the latest snapshot before or at time.
virtual ~Segment() override
Holds info on snapshot data extracted from a time range.
void onConnect(RobotUnitInterfacePrx robotUnitPrx)
SensorValuesMap getSensorValuesLocking(const armem::Time ×tamp, DebugObserverHelper *debugObserver=nullptr) const
ForceTorqueValuesMap forceTorqueValuesMap
Segment(server::MemoryToIceAdapter &iceMemory)
static Duration MicroSeconds(std::int64_t microSeconds)
Constructs a duration in microseconds.
Brief description of class DebugObserverHelper.
armem::MemoryID snapshotID
virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
static Duration MilliSeconds(std::int64_t milliSeconds)
Constructs a duration in milliseconds.
static Eigen::Vector3f ConvertToVector3f(const data::NDArrayPtr &)
std::string predictionEngineID
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override