Segment.cpp
Go to the documentation of this file.
1#include "Segment.h"
2
3// STL
4#include <iterator>
5
6#include <SimoxUtility/math/pose/pose.h>
7#include <SimoxUtility/math/regression/linear.h>
8
10
16#include <RobotAPI/libraries/armem_robot_state/aron/Robot.aron.generated.h>
26
27#include <manif/SE3.h>
28
30{
31
33 Base(memoryToIceAdapter,
34 armem::robot_state::localizationSegmentID.coreSegmentName,
35 arondto::Transform::ToAronType(),
36 1024)
37 {
38 }
39
41 {
42 }
43
44 void
46 {
47 Base::defineProperties(defs, prefix);
48
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).");
53 }
54
55 void
57 {
58 Base::init();
59
60 segmentPtr->addPredictor(armem::PredictionEngine{.engineID = "Linear"},
61 [this](const PredictionRequest& request)
62 { return this->predictLinear(request); });
63 }
64
65 void
67 {
68 }
69
72 {
73 return this->doLocked([this, &timestamp]() { return getRobotFramePoses(timestamp); });
74 }
75
78 {
81
82 RobotFramePoseMap frames;
83 for (const std::string& robotName : segmentPtr->getProviderSegmentNames())
84 {
85 TransformQuery query{
86 .header = {.parentFrame = armarx::GlobalFrame,
88 .agent = robotName,
89 .timestamp = timestamp}};
90
91 const auto result = TransformHelper::lookupTransformChain(*segmentPtr, query);
92 if (not result)
93 {
94 // TODO
95 continue;
96 }
97
98 frames.emplace(robotName, result.transforms);
99 }
100
102 << "Number of known robot pose chains: " << frames.size();
103
104 return frames;
105 }
106
109 {
110 return this->doLocked([this, &timestamp]() { return getRobotGlobalPoses(timestamp); });
111 }
112
115 {
118
119 RobotPoseMap robotGlobalPoses;
120 for (const std::string& robotName : segmentPtr->getProviderSegmentNames())
121 {
122 TransformQuery query{
123 .header = {.parentFrame = GlobalFrame,
125 .agent = robotName,
126 .timestamp = timestamp}};
127
128 if (const auto result = TransformHelper::lookupTransform(*segmentPtr, query))
129 {
130 robotGlobalPoses.emplace(robotName, result.transform.transform);
131 }
132 else
133 {
134 // TODO
135 }
136 }
137
139 << "Number of known robot poses: " << robotGlobalPoses.size();
140
141 return robotGlobalPoses;
142 }
143
144 bool
146 {
147 Commit commit;
148 commit.add(makeUpdate(transform));
149
150 const armem::CommitResult result = iceMemory.commit(commit);
151 return result.allSuccess();
152 }
153
154 bool
157 {
158 Commit commit;
159 commit.add(makeUpdate(transform));
160
161 const armem::CommitResult result = iceMemory.commitLocking(commit);
162 return result.allSuccess();
163 }
164
166 Segment::makeUpdate(const armarx::armem::robot_state::localization::Transform& transform) const
167 {
168 const armem::Time& timestamp = transform.header.timestamp;
169 const MemoryID providerID =
171
172 EntityUpdate update;
173 update.entityID =
174 providerID.withEntityName(transform.header.parentFrame + "," + transform.header.frame);
175 update.arrivedTime = update.referencedTime = update.sentTime = timestamp;
176
177 arondto::Transform aronTransform;
178 toAron(aronTransform, transform);
179 update.instancesData = {aronTransform.toAron()};
180
181 return update;
182 }
183
185 Segment::predictLinear(const PredictionRequest& request)
186 {
187 PredictionResult result;
188 result.snapshotID = request.snapshotID;
189 if (request.predictionSettings.predictionEngineID != "Linear")
190 {
191 result.success = false;
192 result.errorMessage = "Prediction engine " +
194 " is not supported in Proprioception.";
195 return result;
196 }
197
198 static const int tangentDims = 6;
200
201 const DateTime timeOrigin = DateTime::Now();
202 const armarx::Duration timeWindow =
203 Duration::SecondsDouble(properties.predictionTimeWindow);
205
206 doLocked(
207 [&, this]()
208 {
211 request.snapshotID,
212 timeOrigin - timeWindow,
213 timeOrigin,
214 [](const aron::data::DictPtr& data)
215 {
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();
221 },
222 [](const aron::data::DictPtr& data)
223 { return arondto::Transform::FromAron(data); });
224 });
225
226 if (info.success)
227 {
228 Eigen::Matrix4f prediction;
229 if (info.timestampsSec.size() <= 1)
230 {
231 prediction = info.latestValue.transform;
232 }
233 else
234 {
235 using simox::math::LinearRegression;
236 const bool inputOffset = false;
237 const LinearRegression<tangentDims> model = LinearRegression<tangentDims>::Fit(
238 info.timestampsSec, info.values, inputOffset);
239 const auto predictionTime = request.snapshotID.timestamp;
240 Vector6d linearPred =
241 model.predict((predictionTime - timeOrigin).toSecondsDouble());
242 prediction = manif::SE3Tangentd(linearPred).exp().transform().cast<float>();
243 }
244
245 info.latestValue.transform = prediction;
246 result.success = true;
247 result.prediction = info.latestValue.toAron();
248 }
249 else
250 {
251 result.success = false;
252 result.errorMessage = info.errorMessage;
253 }
254
255 return result;
256 }
257
258} // namespace armarx::armem::server::robot_state::localization
std::string timestamp()
static DateTime Now()
Definition DateTime.cpp:51
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.
Definition Logging.cpp:99
MemoryID withProviderSegmentName(const std::string &name) const
Definition MemoryID.cpp:417
MemoryID withEntityName(const std::string &name) const
Definition MemoryID.cpp:425
Helps connecting a Memory server to the Ice interface.
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
Definition Segment.cpp:45
bool commitTransform(const armem::robot_state::localization::Transform &transform)
Definition Segment.cpp:145
RobotFramePoseMap getRobotFramePosesLocking(const armem::Time &timestamp) const
Definition Segment.cpp:71
bool commitTransformLocking(const armem::robot_state::localization::Transform &transform)
Definition Segment.cpp:155
RobotFramePoseMap getRobotFramePoses(const armem::Time &timestamp) const
Definition Segment.cpp:77
RobotPoseMap getRobotGlobalPoses(const armem::Time &timestamp) const
Definition Segment.cpp:114
RobotPoseMap getRobotGlobalPosesLocking(const armem::Time &timestamp) const
Definition Segment.cpp:108
Segment(server::MemoryToIceAdapter &iceMemory)
Definition Segment.cpp:32
virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
auto doLocked(FunctionT &&function) const
Execute function under shared (read) lock.
Represents a point in time.
Definition DateTime.h:25
Represents a duration.
Definition Duration.h:17
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
Definition Duration.cpp:78
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
std::string const GlobalFrame
Variable of the global coordinate system.
Definition FramedPose.h:65
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
Definition Dict.h:42
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...
Definition algorithm.h:351
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Result of a Commit.
Definition Commit.h:111
A bundle of updates to be sent to the memory.
Definition Commit.h:90
EntityUpdate & add()
Definition Commit.cpp:80
An update of an entity for a specific point in time.
Definition Commit.h:26
PredictionSettings predictionSettings
Definition Prediction.h:51
aron::data::DictPtr prediction
Definition Prediction.h:63
Holds info on snapshot data extracted from a time range.