6#include <SimoxUtility/math/pose/pose.h>
7#include <SimoxUtility/math/regression/linear.h>
16#include <RobotAPI/libraries/armem_robot_state/aron/Robot.aron.generated.h>
33 Base(memoryToIceAdapter,
35 arondto::Transform::ToAronType(),
49 defs->optional(properties.predictionTimeWindow,
50 "prediction.TimeWindow",
51 "Duration of time window into the past to use for predictions"
52 " when requested via the PredictingMemoryInterface (in seconds).");
62 {
return this->predictLinear(request); });
83 for (
const std::string& robotName :
segmentPtr->getProviderSegmentNames())
91 const auto result = TransformHelper::lookupTransformChain(*
segmentPtr,
query);
98 frames.emplace(robotName, result.transforms);
102 <<
"Number of known robot pose chains: " << frames.size();
120 for (
const std::string& robotName :
segmentPtr->getProviderSegmentNames())
122 TransformQuery
query{
128 if (
const auto result = TransformHelper::lookupTransform(*
segmentPtr,
query))
130 robotGlobalPoses.emplace(robotName, result.transform.transform);
139 <<
"Number of known robot poses: " << robotGlobalPoses.size();
141 return robotGlobalPoses;
175 update.arrivedTime = update.referencedTime = update.sentTime =
timestamp;
177 arondto::Transform aronTransform;
179 update.instancesData = {aronTransform.toAron()};
194 " is not supported in Proprioception.";
198 static const int tangentDims = 6;
212 timeOrigin - timeWindow,
216 Eigen::Matrix4d mat =
217 arondto::Transform::FromAron(data).transform.cast<double>();
218 manif::SE3d se3(simox::math::position(mat),
219 Eigen::Quaterniond(simox::math::orientation(mat)));
220 return se3.log().coeffs();
223 { return arondto::Transform::FromAron(data); });
228 Eigen::Matrix4f prediction;
235 using simox::math::LinearRegression;
236 const bool inputOffset =
false;
237 const LinearRegression<tangentDims> model = LinearRegression<tangentDims>::Fit(
240 Vector6d linearPred =
241 model.predict((predictionTime - timeOrigin).toSecondsDouble());
242 prediction = manif::SE3Tangentd(linearPred).exp().transform().cast<
float>();
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
MemoryID withProviderSegmentName(const std::string &name) const
MemoryID withEntityName(const std::string &name) const
Helps connecting a Memory server to the Ice interface.
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
bool commitTransform(const armem::robot_state::localization::Transform &transform)
RobotFramePoseMap getRobotFramePosesLocking(const armem::Time ×tamp) const
bool commitTransformLocking(const armem::robot_state::localization::Transform &transform)
RobotFramePoseMap getRobotFramePoses(const armem::Time ×tamp) const
RobotPoseMap getRobotGlobalPoses(const armem::Time ×tamp) const
RobotPoseMap getRobotGlobalPosesLocking(const armem::Time ×tamp) const
Segment(server::MemoryToIceAdapter &iceMemory)
virtual ~Segment() override
virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
auto doLocked(FunctionT &&function) const
Execute function under shared (read) lock.
virtual void init() override
MemoryToIceAdapter & iceMemory
server::wm::CoreSegment * segmentPtr
Represents a point in time.
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
#define ARMARX_VERBOSE
The logging level for verbose information.
std::string const GlobalFrame
Variable of the global coordinate system.
const std::string robotRootNodeName
std::unordered_map< std::string, Eigen::Isometry3f > RobotPoseMap
std::unordered_map< std::string, std::vector< Eigen::Isometry3f > > RobotFramePoseMap
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
void toAron(arondto::MemoryID &dto, const MemoryID &bo)
std::shared_ptr< Dict > DictPtr
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
A bundle of updates to be sent to the memory.
An update of an entity for a specific point in time.
armem::MemoryID snapshotID
PredictionSettings predictionSettings
aron::data::DictPtr prediction
armem::MemoryID snapshotID
std::string predictionEngineID
Holds info on snapshot data extracted from a time range.
std::vector< double > timestampsSec
std::vector< DataType > values