Go to the documentation of this file.
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>
27 #include <manif/SE3.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); });
79 using ::armarx::armem::robot_state::localization::TransformHelper;
80 using ::armarx::armem::robot_state::localization::TransformQuery;
89 .timestamp = timestamp}};
91 const auto result = TransformHelper::lookupTransformChain(*
segmentPtr, query);
98 frames.emplace(robotName, result.transforms);
102 <<
"Number of known robot pose chains: " << frames.size();
116 using ::armarx::armem::robot_state::localization::TransformHelper;
117 using ::armarx::armem::robot_state::localization::TransformQuery;
122 TransformQuery query{
126 .timestamp = timestamp}};
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;
177 arondto::Transform aronTransform;
179 update.instancesData = {aronTransform.toAron()};
194 " is not supported in Proprioception.";
198 static const int tangentDims = 6;
209 info = getSnapshotsInRange<server::wm::CoreSegment, Vector6d, arondto::Transform>(
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); });
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>();
armem::MemoryID snapshotID
std::vector< double > timestampsSec
const MemoryID localizationSegmentID
A bundle of updates to be sent to the memory.
virtual ~Segment() override
Helps connecting a Memory server to the Ice interface.
MatrixXX< 4, 4, float > Matrix4f
const std::string GlobalFrame
void toAron(arondto::MemoryID &dto, const MemoryID &bo)
PredictionSettings predictionSettings
Segment(server::MemoryToIceAdapter &iceMemory)
const std::string robotRootNodeName
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
std::vector< std::string > getProviderSegmentNames() const
server::wm::CoreSegment * segmentPtr
MemoryID withProviderSegmentName(const std::string &name) const
aron::data::DictPtr prediction
virtual void init() override
auto doLocked(FunctionT &&function) const
RobotPoseMap getRobotGlobalPosesLocking(const armem::Time ×tamp) const
RobotPoseMap getRobotGlobalPoses(const armem::Time ×tamp) const
An update of an entity for a specific point in time.
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
bool commitTransformLocking(const armem::robot_state::localization::Transform &transform)
std::vector< DataType > values
void addPredictor(const PredictionEngine &engine, Predictor &&predictor)
bool update(mongocxx::collection &coll, const nlohmann::json &query, const nlohmann::json &update)
bool commitTransform(const armem::robot_state::localization::Transform &transform)
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...
Represents a point in time.
std::shared_ptr< Dict > DictPtr
MemoryID withEntityName(const std::string &name) const
std::unordered_map< std::string, Eigen::Isometry3f > RobotPoseMap
MemoryToIceAdapter & iceMemory
RobotFramePoseMap getRobotFramePosesLocking(const armem::Time ×tamp) const
Holds info on snapshot data extracted from a time range.
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.
std::unordered_map< std::string, std::vector< Eigen::Isometry3f > > RobotFramePoseMap
armem::MemoryID snapshotID
virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
data::CommitResult commitLocking(const data::Commit &commitIce, Time timeArrived)
data::CommitResult commit(const data::Commit &commitIce, Time timeArrived)
RobotFramePoseMap getRobotFramePoses(const armem::Time ×tamp) const
std::string predictionEngineID