Visu.cpp
Go to the documentation of this file.
1 #include "Visu.h"
2 
3 #include <algorithm>
4 #include <exception>
5 #include <string>
6 
7 #include <Eigen/Geometry>
8 
9 #include <SimoxUtility/algorithm/apply.hpp>
10 #include <SimoxUtility/algorithm/get_map_keys_values.h>
11 #include <SimoxUtility/color/Color.h>
12 #include <SimoxUtility/color/ColorMap.h>
13 #include <SimoxUtility/color/hsv.h>
14 #include <SimoxUtility/math/pose.h>
15 
19 #include <ArmarXCore/interface/core/PackagePath.h>
20 
27 #include <RobotAPI/interface/components/TrajectoryPlayerInterface.h>
29 #include <RobotAPI/libraries/armem_laser_scans/aron/LaserScan.aron.generated.h>
32 
34 {
35 
36 
38  {
39  Logging::setTag("Visu");
40  }
41 
42  void
43  Visu::defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix)
44  {
45  defs->optional(
46  p.enabled, prefix + "enabled", "Enable or disable visualization of objects.");
47  defs->optional(p.frequencyHz, prefix + "frequenzyHz", "Frequency of visualization.");
48  defs->optional(
49  p.uniformColor, prefix + "uniformColor", "If enabled, points will be drawn in red.");
50  defs->optional(p.maxRobotAgeMs,
51  prefix + "maxRobotAgeMs",
52  "Maximum age of robot state before a new one is retrieved in milliseconds.");
53  defs->optional(p.colorByIntensity, "colorByIntensity", "");
54  }
55 
56  void
57  Visu::init(const wm::CoreSegment* coreSegment,
58  armem::robot_state::VirtualRobotReader* virtualRobotReader)
59  {
60  this->coreSegment = coreSegment;
61  this->virtualRobotReader = virtualRobotReader;
62  }
63 
64  void
66  {
67  this->arviz = arviz;
68  if (debugObserver)
69  {
70  bool batchMode = true;
71  this->debugObserver = DebugObserverHelper("LaserScansMemory", debugObserver, batchMode);
72  }
73 
74  if (updateTask)
75  {
76  updateTask->stop();
77  updateTask->join();
78  updateTask = nullptr;
79  }
80  updateTask = new SimpleRunningTask<>([this]() { this->visualizeRun(); });
81  updateTask->start();
82  }
83 
84  void
85  Visu::visualizeRun()
86  {
87  CycleUtil cycle(static_cast<int>(1000 / p.frequencyHz));
88  while (updateTask and not updateTask->isStopped())
89  {
90  if (p.enabled)
91  {
92  const Time timestamp = Time::Now();
93  ARMARX_DEBUG << "Visu task at " << armem::toStringMilliSeconds(timestamp);
94 
95  try
96  {
97  visualizeOnce(timestamp);
98  }
99  catch (const std::exception& e)
100  {
101  ARMARX_WARNING << "Caught exception while visualizing robots: \n" << e.what();
102  }
103  catch (...)
104  {
105  ARMARX_WARNING << "Caught unknown exception while visualizing robots.";
106  }
107 
108  if (debugObserver.has_value())
109  {
110  debugObserver->sendDebugObserverBatch();
111  }
112  }
113  cycle.waitForCycleDuration();
114  }
115  }
116 
117  void
118  Visu::visualizeScan(const std::vector<ScanPoint>& points,
119  const std::string& sensorName,
120  const std::string& agentName,
121  const viz::Color& color)
122  {
123  viz::PointCloud pointCloud("laser_scan");
124 
125  ARMARX_VERBOSE << "Point cloud with " << points.size() << " points";
126 
127  for (const auto& point : points)
128  {
129 
130  // ARMARX_INFO << point.intensity;
131  const viz::Color specificColor = [&point, &color, this]() -> viz::Color
132  {
133  if (p.colorByIntensity)
134  {
135  Eigen::Vector3f hsv = simox::color::rgb_to_hsv(
136  Eigen::Vector3f(static_cast<float>(color.r) / 255.f,
137  static_cast<float>(color.g) / 255.f,
138  static_cast<float>(color.b) / 255.f));
139 
140  // ARMARX_INFO << point.intensity;
141 
142  hsv(2) = std::clamp<float>(point.intensity, 0., 1.);
143 
144  const Eigen::Vector3f rgb = simox::color::hsv_to_rgb(hsv);
145 
146  return viz::Color{rgb(0), rgb(1), rgb(2)};
147  }
148 
149  return color;
150  }();
151 
152  pointCloud.addPoint(point.point.x(), point.point.y(), point.point.z(), specificColor);
153  }
154 
155  pointCloud.pointSizeInPixels(3);
156 
157  viz::Layer l = arviz.layer(agentName + "/" + sensorName);
158  l.add(pointCloud);
159 
160  arviz.commit(l);
161  }
162 
163  std::vector<ScanPoint>
165  const Eigen::Isometry3f& global_T_sensor)
166  {
167  const auto scanCartesian =
168  armarx::armem::laser_scans::util::toCartesian<Eigen::Vector3f>(scan.data);
169 
170  std::vector<ScanPoint> points;
171  points.reserve(scan.data.size());
172 
173  for (std::size_t i = 0; i < scan.data.size(); i++)
174  {
175  const auto& point = scanCartesian.at(i);
176  const auto& raw = scan.data.at(i);
177 
178  const Eigen::Vector3f pointGlobal = global_T_sensor * point;
179  points.push_back(ScanPoint{.point = pointGlobal, .intensity = raw.intensity});
180  }
181 
182  return points;
183  }
184 
185  // void Segment::getLatestObjectPoses(const wm::CoreSegment& coreSeg, ObjectPoseMap& out)
186  // {
187  // coreSeg.forEachProviderSegment([&out](const wm::ProviderSegment & provSegment)
188  // {
189  // getLatestObjectPoses(provSegment, out);
190  // });
191  // }
192 
193 
194  // void Segment::getLatestObjectPoses(const wm::ProviderSegment& provSegment, ObjectPoseMap& out)
195  // {
196  // provSegment.forEachEntity([&out](const wm::Entity & entity)
197  // {
198  // if (!entity.empty())
199  // {
200  // ObjectPose pose = getLatestObjectPose(entity);
201  // // Try to insert. Fails and returns false if an entry already exists.
202  // const auto [it, success] = out.insert({pose.objectID, pose});
203  // if (!success)
204  // {
205  // // An entry with that ID already exists. We keep the newest.
206  // if (it->second.timestamp < pose.timestamp)
207  // {
208  // it->second = pose;
209  // }
210  // }
211  // }
212  // });
213  // }
214 
215 
216  // void Segment::getLatestObjectPose(const wm::Entity& entity, ObjectPose& out)
217  // {
218  // entity.getLatestSnapshot().forEachInstance([&out](const wm::EntityInstance & instance)
219  // {
220  // arondto::ObjectInstance dto;
221  // dto.fromAron(instance.data());
222 
223  // fromAron(dto, out);
224  // });
225  // }
226 
227  std::map<std::string, armem::laser_scans::LaserScanStamped>
228  Visu::getCurrentLaserScans()
229  {
230  ARMARX_CHECK_NOT_NULL(coreSegment);
231 
232  const auto convert = [this](const wm::EntityInstance& entityInstance)
234  {
235  const std::optional<armarx::armem::laser_scans::arondto::LaserScanStamped> dto =
236  tryCast<armarx::armem::laser_scans::arondto::LaserScanStamped>(entityInstance);
237 
238  ARMARX_CHECK(dto.has_value());
239 
241  fromAron(dto.value(), laserScanStamped);
242 
243  const auto ndArrayNavigator =
244  aron::data::NDArray::DynamicCast(entityInstance.data()->getElement("scan"));
245 
246  ARMARX_CHECK_NOT_NULL(ndArrayNavigator);
247 
248  laserScanStamped.data =
249  armarx::armem::laser_scans::fromAron<LaserScanStep>(ndArrayNavigator);
250 
251  ARMARX_VERBOSE << "Number of steps: " << laserScanStamped.data.size();
252 
253  return laserScanStamped;
254  };
255 
256  std::map<std::string, armem::laser_scans::LaserScanStamped> scans;
257 
258  const auto applyToInstance = [&](const wm::EntityInstance& instance)
259  {
260  const auto scan = convert(instance);
261  scans[instance.id().providerSegmentName + "/" + instance.id().entityName] = scan;
262  };
263 
264  const auto applyToEntity = [&](const wm::Entity& entity)
265  {
266  if (entity.empty())
267  {
268  return;
269  }
270 
271  const auto& snapshot = entity.getLatestSnapshot();
272 
273  snapshot.forEachInstance(applyToInstance);
274  };
275 
276  const auto applyToProviderSegment = [&](const auto& providerSegment)
277  { providerSegment.forEachEntity(applyToEntity); };
278 
279  coreSegment->forEachProviderSegment(applyToProviderSegment);
280 
281  ARMARX_VERBOSE << scans.size() << " scans";
282  return scans;
283  }
284 
285  void
286  Visu::visualizeOnce(const Time& timestamp)
287  {
288  std::map<std::string, armem::laser_scans::LaserScanStamped> currentLaserScans =
289  getCurrentLaserScans();
290 
291  int i = 0;
292 
293  for (const auto& [provider, scan] : currentLaserScans)
294  {
295  ARMARX_VERBOSE << "Visualizing `" << provider << "`";
296 
297  const auto global_T_sensor = [&]() -> Eigen::Isometry3f
298  {
299  const auto robot = getSynchronizedRobot(scan.header.agent, scan.header.timestamp);
300  if (not robot)
301  {
302  ARMARX_VERBOSE << deactivateSpam(1) << "Robot `" << scan.header.agent << "`"
303  << "not available";
305  }
306 
307  const auto sensorNode = robot->getRobotNode(scan.header.frame);
308  ARMARX_CHECK_NOT_NULL(sensorNode) << "No robot node `" << scan.header.frame
309  << "` for robot `" << scan.header.agent << "`";
310 
311  ARMARX_VERBOSE << "Sensor position for sensor `" << scan.header.frame << "` is "
312  << sensorNode->getGlobalPosition();
313  return Eigen::Isometry3f{sensorNode->getGlobalPose()};
314  }();
315 
316 
317  const std::vector<ScanPoint> points = convertScanToGlobal(scan, global_T_sensor);
318 
319  const auto color = [&]() -> simox::Color
320  {
321  if (p.uniformColor)
322  {
323  return simox::Color::red();
324  }
325 
326  return simox::color::GlasbeyLUT::at(i++);
327  }();
328 
329  visualizeScan(points, scan.header.frame, scan.header.agent, color);
330  }
331  }
332 
334  Visu::getSynchronizedRobot(const std::string& name, const DateTime& timestamp)
335  {
336  if (robots.count(name) == 0)
337  {
338  ARMARX_CHECK_NOT_NULL(virtualRobotReader);
339  const auto robot = virtualRobotReader->getRobot(name);
340 
341  if (robot)
342  {
343  robots[name] = {robot, DateTime::Invalid()};
344  }
345  else
346  {
347  return nullptr;
348  }
349  }
350 
351  auto& entry = robots.at(name);
352  if (entry.second.isInvalid() ||
353  (timestamp - entry.second) > Duration::MilliSeconds(p.maxRobotAgeMs))
354  {
355  if (virtualRobotReader->synchronizeRobot(*entry.first, timestamp))
356  {
357  entry.second = timestamp;
358  }
359  else
360  {
361  ARMARX_INFO << deactivateSpam(10) << "Failed to synchronize robot `" << name << "`";
362  }
363  }
364  return entry.first;
365  }
366 
367 } // namespace armarx::armem::server::laser_scans
armarx::armem::laser_scans::LaserScanStamped
Definition: types.h:40
armarx::SimpleRunningTask
Usage:
Definition: TaskUtil.h:70
armarx::viz::Client::commit
CommitResult commit(StagedCommit const &commit)
Definition: Client.cpp:80
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
armarx::armem::robot_state::VirtualRobotReader
The VirtualRobotReader class.
Definition: VirtualRobotReader.h:40
armarx::armem::server::laser_scans::Visu::Visu
Visu()
Definition: Visu.cpp:37
armarx::armem::robot_state::VirtualRobotReader::getRobot
VirtualRobot::RobotPtr getRobot(const std::string &name, const armem::Time &timestamp=armem::Time::Invalid(), const VirtualRobot::RobotIO::RobotDescription &loadMode=VirtualRobot::RobotIO::RobotDescription::eStructure)
Definition: VirtualRobotReader.cpp:57
armarx::armem::server::laser_scans::Visu::init
void init(const wm::CoreSegment *coreSegment, armem::robot_state::VirtualRobotReader *virtualRobotReader)
Definition: Visu.cpp:57
armarx::armem::wm::EntityInstance
Client-side working entity instance.
Definition: memory_definitions.h:32
armarx::core::time::DateTime::Now
static DateTime Now()
Definition: DateTime.cpp:55
ARMARX_CHECK_NOT_NULL
#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...
Definition: ExpressionException.h:206
armarx::armem::laser_scans::LaserScanStamped::data
LaserScan data
Definition: types.h:43
aron_conversions.h
armarx::CycleUtil
This util class helps with keeping a cycle time during a control cycle.
Definition: CycleUtil.h:40
armarx::armem::robot_state::VirtualRobotReader::synchronizeRobot
bool synchronizeRobot(VirtualRobot::Robot &robot, const armem::Time &timestamp) const
Definition: VirtualRobotReader.cpp:20
types.h
armarx::convert
armem::articulated_object::ArticulatedObject convert(const VirtualRobot::Robot &obj, const armem::Time &timestamp)
Definition: ArticulatedObjectLocalizerDynamicSimulation.cpp:194
armarx::viz::Layer::add
void add(ElementT const &element)
Definition: Layer.h:29
armarx::armem::server::wm::Entity
Definition: memory_definitions.h:30
armarx::armem::server::laser_scans
This file is part of ArmarX.
Definition: LaserScansMemory.cpp:35
armarx::armem::server::laser_scans::Visu::connect
void connect(const viz::Client &arviz, DebugObserverInterfacePrx debugObserver=nullptr)
Definition: Visu.cpp:65
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
Elements.h
armarx::aron::data::detail::SpecializedVariantBase< data::dto::NDArray, NDArray >::DynamicCast
static PointerType DynamicCast(const VariantPtr &n)
Definition: SpecializedVariant.h:117
armarx::armem::server::laser_scans::ScanPoint
Definition: Visu.h:43
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
Color
uint32_t Color
RGBA color.
Definition: color.h:8
armarx::armem::server::laser_scans::Visu::defineProperties
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="visu.")
Definition: Visu.cpp:43
FramedPose.h
Color.h
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::armem::base::CoreSegmentBase::forEachProviderSegment
bool forEachProviderSegment(ProviderSegmentFunctionT &&func)
Definition: CoreSegmentBase.h:217
armarx::viz::Color
Definition: Color.h:13
Visu.h
armarx::armem::toStringMilliSeconds
std::string toStringMilliSeconds(const Time &time, int decimals=3)
Returns time as e.g.
Definition: Time.cpp:11
armarx::armem::server::laser_scans::ScanPoint::point
Eigen::Vector3f point
Definition: Visu.h:45
armarx::viz::PointCloud
Definition: PointCloud.h:21
armarx::armem::server::laser_scans::convertScanToGlobal
std::vector< ScanPoint > convertScanToGlobal(const armem::laser_scans::LaserScanStamped &scan, const Eigen::Isometry3f &global_T_sensor)
Definition: Visu.cpp:164
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::red
QColor red()
Definition: StyleSheets.h:76
CycleUtil.h
armarx::armem::server::wm::CoreSegment
base::CoreSegmentBase
Definition: memory_definitions.h:86
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::armem::fromAron
void fromAron(const arondto::MemoryID &dto, MemoryID &bo)
Definition: aron_conversions.cpp:8
TimeUtil.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
IceUtil::Handle< class PropertyDefinitionContainer >
IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface >
Time.h
armarx::Logging::deactivateSpam
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:92
laser_scanner_conversion.h
util.h
armarx::Logging::setTag
void setTag(const LogTag &tag)
Definition: Logging.cpp:55
Logging.h
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::viz::Client::layer
Layer layer(std::string const &name) const
Definition: Client.cpp:73
armarx::viz::Client
Definition: Client.h:109
armarx::viz::Layer
Definition: Layer.h:12
armarx::DebugObserverHelper
Brief description of class DebugObserverHelper.
Definition: DebugObserverHelper.h:50
armarx::core::time::DateTime::Invalid
static DateTime Invalid()
Definition: DateTime.cpp:60
PointCloud.h
armarx::core::time::Duration::MilliSeconds
static Duration MilliSeconds(std::int64_t milliSeconds)
Constructs a duration in milliseconds.
Definition: Duration.cpp:55
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18