RobotStatePredictionClient.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package RobotAPI::ArmarXObjects::RobotStatePredictionClientExample
17  * @author Rainer Kartmann ( rainer dot kartmann at kit dot edu )
18  * @date 2022
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
24 
26 
32 #include <RobotAPI/libraries/armem_robot_state/aron/Proprioception.aron.generated.h>
33 #include <RobotAPI/libraries/armem_robot_state/aron/Transform.aron.generated.h>
38 
39 #include "simox_alg.hpp"
40 
42 {
43 
45  {
46  }
47 
48  std::vector<armem::MemoryID>
50  {
52  }
53 
54  std::vector<MemoryID>
56  {
58  }
59 
60  std::vector<MemoryID>
61  RobotStatePredictionClient::_queryEntityIDs(const std::string& coreSegmentName)
62  {
64  {
65  namespace qf = armarx::armem::client::query_fns;
66  qb.coreSegments(qf::withName(coreSegmentName))
68  .entities(qf::all())
70  }
72  if (result.success)
73  {
74  return armem::getEntityIDs(result.memory);
75  }
76  else
77  {
78  // ToDo: Use exceptions to escalate error.
79  ARMARX_VERBOSE << "Query failed: " << result.errorMessage;
80  return {};
81  }
82  }
83 
84  std::vector<armem::PredictionRequest>
86  const std::vector<armem::MemoryID>& entityIDs,
87  armem::Time predictedTime,
88  const std::string& engineID)
89  {
90  std::vector<armem::PredictionRequest> requests;
91  requests.reserve(entityIDs.size());
92  for (const armem::MemoryID& entityID : entityIDs)
93  {
94  armem::PredictionRequest& request = requests.emplace_back();
95  request.snapshotID = entityID.withTimestamp(predictedTime);
96  request.predictionSettings.predictionEngineID = engineID;
97  }
98  ARMARX_CHECK_EQUAL(requests.size(), entityIDs.size());
99  return requests;
100  }
101 
102  std::vector<PredictionResult>
103  RobotStatePredictionClient::predict(const std::vector<MemoryID>& entityIDs,
104  Time predictedTime,
105  const std::string& engineID)
106  {
107  const std::vector<PredictionRequest> requests =
108  makePredictionRequests(entityIDs, predictedTime, engineID);
109  return predict(requests);
110  }
111 
112  std::vector<PredictionResult>
113  RobotStatePredictionClient::predict(const std::vector<PredictionRequest>& requests)
114  {
115  const std::vector<PredictionResult> results = remote.reader.predict(requests);
116  ARMARX_CHECK_EQUAL(results.size(), requests.size());
117  return results;
118  }
119 
120  std::optional<Eigen::Affine3f>
122  const std::vector<armem::PredictionResult>& localizationPredictionResults,
123  const std::vector<armem::MemoryID>& localizationEntityIDs,
124  armem::Time predictedTime)
125  {
126  ARMARX_CHECK_EQUAL(localizationPredictionResults.size(), localizationEntityIDs.size());
127  std::stringstream errorMessages;
128 
129  namespace loc = armem::robot_state::localization;
130 
131  std::optional<armem::wm::CoreSegment> coreSegment;
132 
133  loc::TransformQuery query;
134  query.header.parentFrame = armarx::GlobalFrame;
136  query.header.agent = "";
137  query.header.timestamp = predictedTime;
138 
139  for (size_t i = 0; i < localizationPredictionResults.size(); ++i)
140  {
141  const armem::PredictionResult& result = localizationPredictionResults[i];
142  const armem::MemoryID& entityID = localizationEntityIDs.at(i);
143 
144  if (result.success)
145  {
146  if (query.header.agent.empty())
147  {
148  const arondto::Transform tf = arondto::Transform::FromAron(result.prediction);
149  query.header.agent = tf.header.agent;
150  }
151  if (not coreSegment)
152  {
153  coreSegment.emplace(entityID.getCoreSegmentID());
154  }
155  {
157  update.entityID = entityID;
158  update.referencedTime = predictedTime;
159  update.instancesData = {result.prediction};
160  coreSegment->update(update);
161  }
162  }
163  else
164  {
165  errorMessages << "Prediction of '" << entityID << "'"
166  << " failed: " << result.errorMessage << "\n";
167  }
168  }
169 
170  std::optional<Eigen::Affine3f> result;
171  if (coreSegment.has_value())
172  {
173  loc::TransformResult tf =
174  loc::TransformHelper::lookupTransform(coreSegment.value(), query);
175 
176  if (tf)
177  {
178  result = tf.transform.transform;
179  }
180  else
181  {
182  errorMessages << "\nFailed to lookup transform: " << tf.errorMessage << "\n";
183  }
184  }
185 
186  if (not errorMessages.str().empty())
187  {
188  // ToDo: Introduce an exception here?
189  ARMARX_VERBOSE << errorMessages.str();
190  }
191  return result;
192  }
193 
194  std::optional<std::map<std::string, float>>
196  const std::vector<PredictionResult>& proprioceptionPredictionResults,
197  const std::string& robotName)
198  {
199  auto it = std::find_if(proprioceptionPredictionResults.begin(),
200  proprioceptionPredictionResults.end(),
201  [&robotName](const PredictionResult& result)
202  { return result.snapshotID.entityName == robotName; });
203  if (it != proprioceptionPredictionResults.end())
204  {
205  auto result = *it;
206  auto prop = armem::arondto::Proprioception::FromAron(result.prediction);
207  return prop.joints.position;
208  }
209  else
210  {
211  return std::nullopt;
212  }
213  }
214 
215  std::optional<Eigen::Affine3f>
216  RobotStatePredictionClient::predictGlobalPose(const std::vector<MemoryID>& entityIDs,
217  Time predictedTime,
218  const std::string& engineID)
219  {
220  const std::vector<PredictionResult> results = predict(entityIDs, predictedTime, engineID);
221  std::optional<Eigen::Affine3f> pose = lookupGlobalPose(results, entityIDs, predictedTime);
222  return pose;
223  }
224 
225  std::optional<std::map<std::string, float>>
226  RobotStatePredictionClient::predictJointPositions(const std::vector<MemoryID>& entityIDs,
227  Time predictedTime,
228  const std::string& robotName,
229  const std::string& engineID)
230  {
231  const std::vector<PredictionResult> results = predict(entityIDs, predictedTime, engineID);
232  return lookupJointPositions(results, robotName);
233  }
234 
236  RobotStatePredictionClient::predictWholeBody(const std::vector<armem::MemoryID>& locEntityIDs,
237  const std::vector<armem::MemoryID>& propEntityIDs,
238  Time predictedTime,
239  const std::string& robotName,
240  const std::string& engineID)
241  {
243 
244  // Predict.
245  const std::vector<armem::MemoryID> entityIDs =
246  simox::alg::concatenate(locEntityIDs, propEntityIDs);
247 
248  if (entityIDs.empty())
249  {
250  return result;
251  }
252 
253  auto _results = predict(entityIDs, predictedTime, "Linear");
254 
255  // Gather results.
256  std::vector<armem::PredictionResult> locResults, propResults;
257  locResults = simox::alg::slice(_results, 0, locEntityIDs.size());
258  propResults = simox::alg::slice(_results, locEntityIDs.size());
259  ARMARX_CHECK_EQUAL(locResults.size(), locEntityIDs.size());
260  ARMARX_CHECK_EQUAL(propResults.size(), propEntityIDs.size());
261 
262 
263  result.globalPose = lookupGlobalPose(locResults, locEntityIDs, predictedTime);
264  result.jointPositions = lookupJointPositions(propResults, robotName);
265 
266  return result;
267  }
268 
269 } // namespace armarx::armem::robot_state
armarx::armem::detail::SuccessHeader::success
bool success
Definition: SuccessHeader.h:19
simox::alg::slice
std::vector< Args... > slice(const std::vector< Args... > &vector, size_t start=0, std::optional< size_t > end=std::nullopt)
Definition: Impl.cpp:95
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:187
armarx::armem::robot_state::RobotStatePredictionClient::lookupJointPositions
std::optional< std::map< std::string, float > > lookupJointPositions(const std::vector< armem::PredictionResult > &proprioceptionPredictionResults, const std::string &robotName)
Definition: RobotStatePredictionClient.cpp:195
armarx::armem::PredictionRequest
Definition: Prediction.h:48
armarx::armem::robot_state::RobotStatePredictionClient::remote
Remote remote
Definition: RobotStatePredictionClient.h:103
armarx::armem::client::query::ProviderSegmentSelector::entities
EntitySelector & entities()
Start specifying entities.
Definition: selectors.cpp:135
armarx::armem::client::QueryResult::memory
wm::Memory memory
The slice of the memory that matched the query.
Definition: Query.h:58
query.h
armarx::armem::robot_state::RobotStatePredictionClient::Remote::reader
armem::client::Reader reader
Definition: RobotStatePredictionClient.h:99
armarx::armem::robot_state::RobotStatePredictionClient::WholeBodyPrediction
Definition: RobotStatePredictionClient.h:43
armarx::armem::client::query::EntitySelector::snapshots
SnapshotSelector & snapshots()
Start specifying entity snapshots.
Definition: selectors.cpp:92
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:65
armarx::armem::PredictionRequest::predictionSettings
PredictionSettings predictionSettings
Definition: Prediction.h:51
constants.h
armarx::armem::robot_state::RobotStatePredictionClient::RobotStatePredictionClient
RobotStatePredictionClient()
Definition: RobotStatePredictionClient.cpp:44
armarx::armem::robot_state::constants::proprioceptionCoreSegment
const std::string proprioceptionCoreSegment
Definition: constants.h:30
armarx::armem::robot_state
Definition: RobotStatePredictionClient.cpp:41
armarx::armem::robot_state::RobotStatePredictionClient::queryProprioceptionEntityIDs
std::vector< armem::MemoryID > queryProprioceptionEntityIDs()
Definition: RobotStatePredictionClient.cpp:55
RobotStatePredictionClient.h
armarx::armem::robot_state::RobotStatePredictionClient::WholeBodyPrediction::globalPose
std::optional< Eigen::Affine3f > globalPose
Definition: RobotStatePredictionClient.h:45
armarx::armem::client::QueryResult
Result of a QueryInput.
Definition: Query.h:50
armarx::armem::robot_state::constants::robotRootNodeName
const std::string robotRootNodeName
Definition: constants.h:36
armarx::armem::client::query_fns::withName
auto withName(const std::string &name)
Definition: query_fns.h:23
armarx::armem::PredictionResult
Definition: Prediction.h:57
armarx::armem::robot_state::RobotStatePredictionClient::predict
std::vector< armem::PredictionResult > predict(const std::vector< armem::MemoryID > &entityIDs, armem::Time predictedTime, const std::string &engineID="Linear")
Definition: RobotStatePredictionClient.cpp:103
TransformHelper.h
armarx::armem::client::Reader::predict
std::vector< PredictionResult > predict(const std::vector< PredictionRequest > &requests) const
Get a prediction for the state of multiple entity instances in the future.
Definition: Reader.cpp:482
armarx::armem::client::query_fns::all
auto all()
Definition: query_fns.h:9
armarx::armem::detail::SuccessHeader::errorMessage
std::string errorMessage
Definition: SuccessHeader.h:20
armarx::armem::MemoryID
A memory ID.
Definition: MemoryID.h:47
armarx::armem::PredictionResult::prediction
aron::data::DictPtr prediction
Definition: Prediction.h:63
FramedPose.h
armarx::armem::client::query::Builder::coreSegments
CoreSegmentSelector & coreSegments()
Start specifying core segments.
Definition: Builder.cpp:42
error.h
armarx::armem::EntityUpdate
An update of an entity for a specific point in time.
Definition: Commit.h:25
aron_conversions.h
operations.h
armarx::armem::server::ltm::util::mongodb::detail::update
bool update(mongocxx::collection &coll, const nlohmann::json &query, const nlohmann::json &update)
Definition: mongodb.cpp:68
memory_definitions.h
armarx::armem::robot_state::RobotStatePredictionClient::predictJointPositions
std::optional< std::map< std::string, float > > predictJointPositions(const std::vector< armem::MemoryID > &entityIDs, armem::Time predictedTime, const std::string &robotName, const std::string &engineID="Linear")
Definition: RobotStatePredictionClient.cpp:226
ExpressionException.h
armarx::armem::client::query_fns::latest
std::function< void(query::SnapshotSelector &)> latest()
Definition: query_fns.h:81
armarx::armem::robot_state::RobotStatePredictionClient::queryLocalizationEntityIDs
std::vector< armem::MemoryID > queryLocalizationEntityIDs()
Definition: RobotStatePredictionClient.cpp:49
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::armem::MemoryID::getCoreSegmentID
MemoryID getCoreSegmentID() const
Definition: MemoryID.cpp:294
armarx::armem::robot_state::RobotStatePredictionClient::predictGlobalPose
std::optional< Eigen::Affine3f > predictGlobalPose(const std::vector< armem::MemoryID > &entityIDs, armem::Time predictedTime, const std::string &engineID="Linear")
Definition: RobotStatePredictionClient.cpp:216
simox_alg.hpp
armarx::armem::robot_state::RobotStatePredictionClient::predictWholeBody
WholeBodyPrediction predictWholeBody(const std::vector< armem::MemoryID > &localizationEntityIDs, const std::vector< armem::MemoryID > &proprioceptionEntityIDs, armem::Time predictedTime, const std::string &robotName, const std::string &engineID="Linear")
Definition: RobotStatePredictionClient.cpp:236
armarx::armem::robot_state::constants::localizationCoreSegment
const std::string localizationCoreSegment
Definition: constants.h:29
armarx::armem::PredictionResult::errorMessage
std::string errorMessage
Definition: Prediction.h:60
armarx::armem::robot_state::RobotStatePredictionClient::makePredictionRequests
std::vector< armem::PredictionRequest > makePredictionRequests(const std::vector< armem::MemoryID > &entityIDs, armem::Time predictedTime, const std::string &engineID="Linear")
Definition: RobotStatePredictionClient.cpp:85
armarx::armem::getEntityIDs
std::vector< MemoryID > getEntityIDs(const ContainerT &container)
Definition: operations.h:51
simox::alg::concatenate
std::vector< Args... > concatenate(const std::vector< Args... > &lhs, const std::vector< Args... > &rhs)
Definition: Impl.cpp:44
armarx::armem::robot_state::RobotStatePredictionClient::lookupGlobalPose
std::optional< Eigen::Affine3f > lookupGlobalPose(const std::vector< armem::PredictionResult > &localizationPredictionResults, const std::vector< armem::MemoryID > &localizationEntityIDs, armem::Time predictedTime)
Definition: RobotStatePredictionClient.cpp:121
armarx::armem::MemoryID::withTimestamp
MemoryID withTimestamp(Time time) const
Definition: MemoryID.cpp:433
armarx::armem::client::query::Builder
The query::Builder class provides a fluent-style specification of hierarchical queries.
Definition: Builder.h:21
armarx::armem::client::query::CoreSegmentSelector::providerSegments
ProviderSegmentSelector & providerSegments()
Start specifying provider segments.
Definition: selectors.cpp:178
MemoryNameSystem.h
armarx::armem::PredictionResult::success
bool success
Definition: Prediction.h:59
ARMARX_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
armarx::armem::PredictionRequest::snapshotID
armem::MemoryID snapshotID
Definition: Prediction.h:50
armarx::armem::client::query_fns
Definition: query_fns.h:5
armarx::armem::client::Reader::query
QueryResult query(const QueryInput &input) const
Perform a query.
Definition: Reader.cpp:32
armarx::armem::robot_state::RobotStatePredictionClient::WholeBodyPrediction::jointPositions
std::optional< std::map< std::string, float > > jointPositions
Definition: RobotStatePredictionClient.h:46
armarx::armem::PredictionSettings::predictionEngineID
std::string predictionEngineID
Definition: Prediction.h:42