LaserScannerSimulation.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 ArmarXSimulation::ArmarXObjects::LaserScannerSimulation
17 * @author Fabian Paus ( fabian dot paus at kit dot edu )
18 * @date 2017
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
24
25#include <chrono>
26#include <cmath>
27#include <cstddef>
28#include <memory>
29
30#include <Eigen/Geometry>
31
32#include <SimoxUtility/shapes/AxisAlignedBoundingBox.h>
33#include <SimoxUtility/shapes/OrientedBox.h>
34#include <VirtualRobot/BoundingBox.h>
35#include <VirtualRobot/CollisionDetection/CollisionChecker.h>
36#include <VirtualRobot/CollisionDetection/CollisionModel.h>
37#include <VirtualRobot/Robot.h>
38#include <VirtualRobot/SceneObjectSet.h>
39#include <VirtualRobot/VirtualRobot.h>
40#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h>
41#include <VirtualRobot/Visualization/VisualizationFactory.h>
42
47
49
50#include "ArVizDrawer.h"
51
53{
54
55 static std::size_t
56 nextMultipleOf(std::size_t value, std::size_t multiple)
57 {
58 if (multiple == 0)
59 {
60 return value;
61 }
62
63 std::size_t remainder = value % multiple;
64 if (remainder == 0)
65 {
66 return value;
67 }
68
69 return value + multiple - remainder;
70 }
71
72 static std::vector<std::string>
73 splitProperty(Property<std::string> prop)
74 {
75 std::string propString(prop.getValue());
76 std::vector<std::string> result = Split(propString, ",");
77 return result;
78 }
79
81
83 LaserScannerSimulation::calculateGridDimension(
84 const std::vector<VirtualRobot::BoundingBox>& boundingBoxes) const
85 {
86 simox::AxisAlignedBoundingBox box;
87 for (const auto& boundingBox : boundingBoxes)
88 {
89 box.expand_to(boundingBox.getMin());
90 box.expand_to(boundingBox.getMax());
91 }
92
93 const auto extents = box.extents();
94
95 std::size_t gridSizeX = static_cast<std::size_t>(std::ceil(extents.x() / gridCellSize));
96 gridSizeX = nextMultipleOf(gridSizeX, sizeof(std::size_t) * CHAR_BIT);
97
98 std::size_t gridSizeY = static_cast<std::size_t>(std::ceil(extents.y() / gridCellSize));
99 gridSizeY = nextMultipleOf(gridSizeY, sizeof(std::size_t) * CHAR_BIT);
100
101 return {.originX = box.min_x(),
102 .originY = box.min_y(),
103 .sizeX = std::max<std::size_t>(gridSizeX, 1),
104 .sizeY = std::max<std::size_t>(gridSizeY, 1)};
105 }
106
107 VirtualRobot::SceneObjectSetPtr
108 LaserScannerSimulation::getCollisionObjects(
109 const std::vector<VirtualRobot::SceneObjectPtr>& sceneObjects) const
110 {
111 VirtualRobot::SceneObjectSetPtr objects(new VirtualRobot::SceneObjectSet());
112
113 for (auto& object : sceneObjects)
114 {
115 VirtualRobot::Robot* robot = dynamic_cast<VirtualRobot::Robot*>(object.get());
116 if (robot == nullptr) // standard scene object
117 {
118 objects->addSceneObject(object);
119 }
120 else // passive robot
121 {
122 for (const auto& rns : robot->getRobotNodeSets())
123 {
124 objects->addSceneObjects(rns);
125 }
126 }
127 }
128
129 return objects;
130 }
131
133 LaserScannerSimulation::calculateGridDimension(
134 const std::vector<VirtualRobot::SceneObjectPtr>& sceneObjects) const
135 {
136 VirtualRobot::SceneObjectSetPtr objectSet(new VirtualRobot::SceneObjectSet());
137
138 for (auto& object : sceneObjects)
139 {
140 VirtualRobot::Robot* robot = dynamic_cast<VirtualRobot::Robot*>(object.get());
141 if (robot == nullptr) // standard scene object
142 {
143 objectSet->addSceneObject(object);
144 }
145 else // passive robot
146 {
147 // for (const auto rns : robot->getRobotNodeSets())
148 // {
149 // objects->addSceneObjects(rns);
150 // }
151 objectSet->addSceneObject(object); // This is not working properly
152 }
153 }
154
155 // Create a occupancy grid
156 return calculateGridDimension(objectSet);
157 }
158
159 std::vector<VirtualRobot::BoundingBox>
160 LaserScannerSimulation::boundingBoxes(VirtualRobot::SceneObjectSetPtr const& objects) const
161 {
162 std::vector<VirtualRobot::BoundingBox> objectBoudingBoxes;
163
164 for (unsigned int objIndex = 0; objIndex < objects->getSize(); ++objIndex)
165 {
166 VirtualRobot::SceneObjectPtr object = objects->getSceneObject(objIndex);
167
168 VirtualRobot::Robot* robot = dynamic_cast<VirtualRobot::Robot*>(object.get());
169 if (robot == nullptr) // standard scene object
170 {
171 objectBoudingBoxes.push_back(object->getCollisionModel()->getBoundingBox());
172 }
173 else // passive robot
174 {
175 for (const auto& collisionModel : robot->getCollisionModels())
176 {
177 if (collisionModel->getCollisionModelImplementation()->getPQPModel())
178 {
179 objectBoudingBoxes.push_back(collisionModel->getBoundingBox());
180 }
181 }
182 }
183 }
184
185 return objectBoudingBoxes;
186 }
187
189 LaserScannerSimulation::calculateGridDimension(
190 VirtualRobot::SceneObjectSetPtr const& objects) const
191 {
192 if (objects->getSize() == 0)
193 {
194 return {.originX = 0.0F, .originY = 0.0F, .sizeX = 1, .sizeY = 1};
195 }
196
197 const auto objectBoundingBoxes = boundingBoxes(objects);
198 ARMARX_INFO << objectBoundingBoxes.size() << " bounding boxes";
199
200 // arvizDrawer->drawBoundingBoxes(objectBoundingBoxes);
201
202 return calculateGridDimension(objectBoundingBoxes);
203 }
204
205 void
206 LaserScannerSimulation::fillOccupancyGrid(
207 std::vector<VirtualRobot::SceneObjectPtr> const& sceneObjects)
208 {
209 // initialize grid
210 const auto gridDim = calculateGridDimension(sceneObjects);
211 grid.init(gridDim.sizeX, gridDim.sizeY, gridDim.originX, gridDim.originY, gridCellSize);
212
213 ARMARX_INFO_S << "Creating grid with size (" << gridDim.sizeX << ", " << gridDim.sizeY
214 << ")";
215
216 VirtualRobot::CollisionCheckerPtr collisionChecker =
217 VirtualRobot::CollisionChecker::getGlobalCollisionChecker();
218 VirtualRobot::VisualizationFactoryPtr factory(new VirtualRobot::CoinVisualizationFactory());
219
220 // collision checking by sliding an object with the grid step size over the grid map
221 float boxSize = 1.1f * gridCellSize;
222 VirtualRobot::VisualizationNodePtr boxVisu = factory->createBox(
223 boxSize, boxSize, boxSize, VirtualRobot::VisualizationFactory::Color::Green());
224 VirtualRobot::CollisionModelPtr boxCollisionModel(
225 new VirtualRobot::CollisionModel(boxVisu, "", collisionChecker));
226 VirtualRobot::SceneObjectPtr box(
227 new VirtualRobot::SceneObject("my_box", boxVisu, boxCollisionModel));
228
229 if (not collisionChecker)
230 {
231 ARMARX_WARNING_S << "No global collision checker found";
232 return;
233 }
234
235 ARMARX_INFO_S << "Filling occupancy grid";
236 const auto collisionObjects = getCollisionObjects(sceneObjects);
237
238 for (std::size_t indexY = 0; indexY < grid.sizeY; ++indexY)
239 {
240 for (std::size_t indexX = 0; indexX < grid.sizeX; ++indexX)
241 {
242 const Eigen::Vector2f pos = grid.getCentralPosition(indexX, indexY);
243 const Eigen::Vector3f boxPos(pos.x(), pos.y(), boxPosZ);
244 const Eigen::Matrix4f boxPose =
245 Eigen::Affine3f(Eigen::Translation3f(boxPos)).matrix();
246 box->setGlobalPose(boxPose);
247 // - Check collisions with the other objects
248 const bool collision = collisionChecker->checkCollision(box, collisionObjects);
249 // - Mark each field as occupied or free
250 grid.setOccupied(indexX, indexY, collision);
251 }
252 }
253 }
254
255 void
257 {
258 scanners.clear();
259
260 // Necessary to initialize SoDB and Qt, SoQt::init (otherwise the application crashes at startup)
261 VirtualRobot::init("SimulatorViewerApp");
263 getIceProperties(), getName() + "_PhysicsWorldVisualization");
264 getArmarXManager()->addObject(worldVisu);
265
266 enableVisualization = getProperty<bool>("visualization.enable").getValue();
267 ARMARX_INFO << "Visualization will be " << (enableVisualization ? "enabled" : "disabled");
268
269 topicName = getProperty<std::string>("LaserScannerTopicName").getValue();
270 ARMARX_INFO << "Reporting on topic \"" << topicName << "\"";
271 offeringTopic(topicName);
272
273 robotStateName = getProperty<std::string>("RobotStateComponentName").getValue();
274 ARMARX_INFO << "Using RobotStateComponent \"" << robotStateName << "\"";
275 usingProxy(robotStateName);
276
277 debugDrawerName = getProperty<std::string>("DebugDrawerTopicName").getValue();
278 ARMARX_INFO << "Using DebugDrawerTopic \"" << debugDrawerName << "\"";
279 // No usingProxy for the DebugDrawerTopic? or is it a topic?
280
281 topicReplayerDummy = getProperty<bool>("TopicReplayerDummy").getValue();
282 updatePeriod = getProperty<int>("UpdatePeriod").getValue();
283 visuUpdateFrequency = getProperty<int>("VisuUpdateFrequency").getValue();
284 gridCellSize = getProperty<float>("GridCellSize").getValue();
285
286 auto framesStrings = splitProperty(getProperty<std::string>("Frames"));
287 auto deviceStrings = splitProperty(getProperty<std::string>("Devices"));
288 auto minAnglesStrings = splitProperty(getProperty<std::string>("MinAngles"));
289 auto maxAnglesStrings = splitProperty(getProperty<std::string>("MaxAngles"));
290 auto stepsStrings = splitProperty(getProperty<std::string>("Steps"));
291 auto noiseStrings = splitProperty(getProperty<std::string>("NoiseStdDev"));
292 std::size_t scannerSize = framesStrings.size();
293 if (deviceStrings.size() == 1)
294 {
295 deviceStrings.resize(scannerSize, deviceStrings.front());
296 }
297 else if (deviceStrings.size() != scannerSize)
298 {
299 ARMARX_WARNING << "Unexpected size of property Devices (expected " << scannerSize
300 << " but got " << deviceStrings.size() << ")";
301 return;
302 }
303 if (minAnglesStrings.size() == 1)
304 {
305 minAnglesStrings.resize(scannerSize, minAnglesStrings.front());
306 }
307 else if (minAnglesStrings.size() != scannerSize)
308 {
309 ARMARX_WARNING << "Unexpected size of property MinAngles (expected " << scannerSize
310 << " but got " << minAnglesStrings.size() << ")";
311 return;
312 }
313 if (maxAnglesStrings.size() == 1)
314 {
315 maxAnglesStrings.resize(scannerSize, maxAnglesStrings.front());
316 }
317 else if (maxAnglesStrings.size() != scannerSize)
318 {
319 ARMARX_WARNING << "Unexpected size of property MaxAngles (expected " << scannerSize
320 << " but got " << maxAnglesStrings.size() << ")";
321 return;
322 }
323 if (stepsStrings.size() == 1)
324 {
325 stepsStrings.resize(scannerSize, stepsStrings.front());
326 }
327 else if (stepsStrings.size() != scannerSize)
328 {
329 ARMARX_WARNING << "Unexpected size of property Steps (expected " << scannerSize
330 << " but got " << stepsStrings.size() << ")";
331 return;
332 }
333 if (noiseStrings.size() == 1)
334 {
335 noiseStrings.resize(scannerSize, noiseStrings.front());
336 }
337 else if (noiseStrings.size() != scannerSize)
338 {
339 ARMARX_WARNING << "Unexpected size of property NoiseStdDev (expected " << scannerSize
340 << " but got " << noiseStrings.size() << ")";
341 return;
342 }
343
344 scanners.reserve(scannerSize);
345 connectedDevices.clear();
346 for (std::size_t i = 0; i < scannerSize; ++i)
347 {
348 LaserScannerSimUnit scanner;
349 scanner.frame = framesStrings[i];
350 try
351 {
352 scanner.minAngle = std::stof(minAnglesStrings[i]);
353 scanner.maxAngle = std::stof(maxAnglesStrings[i]);
354 scanner.noiseStdDev = std::stof(noiseStrings[i]);
355 scanner.steps = std::stoi(stepsStrings[i]);
356 }
357 catch (std::exception const& ex)
358 {
359 ARMARX_INFO << "Scanner[" << i << "] Config error: " << ex.what();
360 continue;
361 }
362
363 scanners.push_back(scanner);
364
365 LaserScannerInfo info;
366 info.device = topicReplayerDummy ? deviceStrings[i] : scanner.frame;
367 info.frame = scanner.frame;
368 info.minAngle = scanner.minAngle;
369 info.maxAngle = scanner.maxAngle;
370 info.stepSize = (info.maxAngle - info.minAngle) / scanner.steps;
371 connectedDevices.push_back(info);
372
373 ARMARX_INFO << "Scanner[" << i << "]: " << scanner.frame << ", " << scanner.minAngle
374 << ", " << scanner.maxAngle << ", " << scanner.steps;
375 }
376 }
377
378 void
380 {
381 if (topicReplayerDummy)
382 {
383 ARMARX_INFO << "Fake connect (component is used for topic replay)";
384 return;
385 }
386 topic = getTopic<LaserScannerUnitListenerPrx>(topicName);
387 robotState = getProxy<RobotStateComponentInterfacePrx>(robotStateName);
388 sharedRobot = robotState->getSynchronizedRobot();
389 debugDrawer = getTopic<DebugDrawerInterfacePrx>(debugDrawerName);
390
391 for (LaserScannerSimUnit& scanner : scanners)
392 {
393 try
394 {
395 scanner.frameNode = sharedRobot->getRobotNode(scanner.frame);
396 }
397 catch (std::exception const& ex)
398 {
399 ARMARX_WARNING << "Error while querying robot frame: " << scanner.frame << " "
400 << ex.what();
401 scanner.frameNode = nullptr;
402 }
403
404 if (!scanner.frameNode)
405 {
406 ARMARX_WARNING << "Tried to use a non-existing robot node as frame for the "
407 "laser scanner simulation: "
408 << scanner.frame;
409 }
410 }
411
412 if (task)
413 {
414 task->stop();
415 }
416
417 if (enableVisualization)
418 {
419 arvizDrawer = std::make_unique<ArVizDrawer>(getArvizClient());
420 }
421
422 // Don't forget to sync the data otherwise there may be no objects
423 std::vector<VirtualRobot::SceneObjectPtr> objects;
424 while (objects.empty())
425 {
426 worldVisu->synchronizeVisualizationData();
427 objects = worldVisu->getObjects();
428 ARMARX_INFO << deactivateSpam(5) << "Got " << objects.size()
429 << " objects from the simulator";
430 if (objects.empty())
431 {
433 << "Could not get any objects from the simulator after syncing";
435 }
436 }
437
438 std::vector<VirtualRobot::RobotPtr> robots;
439 while (robots.empty())
440 {
441 worldVisu->synchronizeVisualizationData();
442 robots = worldVisu->getRobots();
443
444 if (robots.empty())
445 {
447 << "Could not get any robots from the simulator after syncing";
449 }
450 }
451
452 ARMARX_INFO << deactivateSpam(5) << "Got " << robots.size() << " robots from the simulator";
453
454 // remove active robots as they might move
455 robots.erase(std::remove_if(robots.begin(),
456 robots.end(),
457 [](const auto& r) -> bool { return not r->isPassive(); }),
458 robots.end());
459
460 ARMARX_INFO << "Got " << objects.size() << " scene objects from the simulator";
461
462 std::vector<VirtualRobot::SceneObjectPtr> validObjects;
463 for (VirtualRobot::SceneObjectPtr const& o : objects)
464 {
465 VirtualRobot::CollisionModelPtr cm = o->getCollisionModel();
466 if (!cm)
467 {
468 ARMARX_WARNING << "Scene object with no collision model: " << o->getName();
469 continue;
470 }
471
472 const auto pqpModel = cm->getCollisionModelImplementation()->getPQPModel();
473 if (pqpModel)
474 {
475 validObjects.push_back(o);
476 }
477 else
478 {
479 ARMARX_WARNING << "PQP model is not filled: " << o->getName();
480 }
481 }
482
483 // robots consist of multiple collision models
484 validObjects.insert(validObjects.end(), robots.begin(), robots.end());
485
486 fillOccupancyGrid(validObjects);
487
488 if (arvizDrawer)
489 {
490 arvizDrawer->drawOccupancyGrid(grid, boxPosZ);
491 }
492
493 visuThrottler = std::make_unique<Throttler>(visuUpdateFrequency);
494
496 &LaserScannerSimulation::updateScanData,
497 updatePeriod,
498 false,
499 "LaserScannerSimUpdate");
500 task->start();
501 }
502
503 void
505 {
506 if (task)
507 {
508 task->stop();
509 task = nullptr;
510 }
511 }
512
513 void
515 {
516 if (worldVisu)
517 {
518 getArmarXManager()->removeObjectBlocking(worldVisu);
519 worldVisu = nullptr;
520 }
521 }
522
529
530 std::string
532 {
533 return topicName;
534 }
535
536 LaserScannerInfoSeq
538 {
539 return connectedDevices;
540 }
541
542 void
543 LaserScannerSimulation::updateScanData()
544 {
545 auto startTime = armarx::Clock::Now();
547
548 const bool updateVisu =
549 enableVisualization and visuThrottler->check(TimeUtil::GetTime().toMicroSeconds());
550
551 for (LaserScannerSimUnit const& scanner : scanners)
552 {
553 if (!scanner.frameNode)
554 {
555 continue;
556 }
557 PosePtr scannerPoseP = PosePtr::dynamicCast(scanner.frameNode->getGlobalPose());
558 Eigen::Matrix4f scannerPose = scannerPoseP->toEigen();
559 Eigen::Vector2f position = scannerPose.col(3).head<2>();
560
561 Eigen::Matrix3f scannerRot = scannerPose.block<3, 3>(0, 0);
562 Eigen::Vector2f yWorld(0.0f, 1.0f);
563 Eigen::Vector2f yScanner = scannerRot.col(1).head<2>();
564 float theta = acos(yWorld.dot(yScanner));
565 if (yScanner.x() >= 0.0f)
566 {
567 theta = -theta;
568 }
569
570 float minAngle = scanner.minAngle;
571 float maxAngle = scanner.maxAngle;
572 int scanSteps = scanner.steps;
573
574 LaserScan scan;
575 scan.reserve(scanSteps);
576
577 // those scan lines would go through the robot
578 // const Interval skipInterval(M_PI_2f32, M_PIf32);
579 const Interval skipInterval(0.0, M_PI_2);
580
581 std::normal_distribution<float> dist(0.0f, scanner.noiseStdDev);
582 for (int i = 0; i < scanSteps; ++i)
583 {
584 LaserScanStep step;
585 step.angle = minAngle + i * (maxAngle - minAngle) / (scanSteps - 1);
586
587 if (skipInterval.contains(step.angle))
588 {
589 continue;
590 }
591
592 const Eigen::Vector2f scanDirGlobal =
593 Eigen::Rotation2Df(step.angle + theta) * Eigen::Vector2f(0.0f, 1.0f);
594 const float distance = grid.computeDistance(position, scanDirGlobal);
595 if (distance > 0.0f)
596 {
597 step.distance = distance + dist(engine);
598 scan.push_back(step);
599 }
600 }
601
602 topic->reportSensorValues(scanner.frame, scanner.frame, scan, now);
603
604 if (updateVisu)
605 {
606 arvizDrawer->prepareScan(scan, scanner.frame, Eigen::Affine3f(scannerPose));
607 }
608 }
609
610 if (updateVisu)
611 {
612 arvizDrawer->drawScans();
613 }
614
615 auto endTime = armarx::Clock::Now();
616 auto timeElapsed = endTime - startTime;
617
619 << "Time to simulate laser scanners: " << timeElapsed.toMilliSecondsDouble()
620 << " ms";
621 }
622
623} // namespace armarx::laser_scanner_simulation
armarx::viz::Client & getArvizClient()
static DateTime Now()
Current time on the virtual clock.
Definition Clock.cpp:93
static TPtr create(Ice::PropertiesPtr properties=Ice::createProperties(), const std::string &configName="", const std::string &configDomain="ArmarX")
Factory method for a component.
Definition Component.h:116
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition Component.cpp:90
Property< PropertyType > getProperty(const std::string &name)
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
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
TopicProxyType getTopic(const std::string &name)
Returns a proxy of the specified topic.
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
std::string getName() const
Retrieve name of object.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
ArmarXManagerPtr getArmarXManager() const
Returns the ArmarX manager used to add and remove components.
The periodic task executes one thread method repeatedly using the time period specified in the constr...
Ice::PropertiesPtr getIceProperties() const
Returns the set of Ice properties.
static IceUtil::Time GetTime(TimeMode timeMode=TimeMode::VirtualTime)
Get the current time.
Definition TimeUtil.cpp:42
static void MSSleep(int durationMS)
lock the calling thread for a given duration (like usleep(...) but using Timeserver time)
Definition TimeUtil.cpp:100
Implements a Variant type for timestamps.
std::string getReportTopicName(const Ice::Current &) const override
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
LaserScannerInfoSeq getConnectedDevices(const Ice::Current &) const override
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_INFO_S
Definition Logging.h:202
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
#define ARMARX_WARNING_S
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:213
std::vector< std::string > Split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
IceInternal::Handle< Pose > PosePtr
Definition Pose.h:306
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
IceInternal::Handle< TimestampVariant > TimestampVariantPtr
std::shared_ptr< Value > value()
Definition cxxopts.hpp:855
double distance(const Point &a, const Point &b)
Definition point.hpp:95