moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
world_diff.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Acorn Pooley, Ioan Sucan */
36
38#include <functional>
39
40namespace collision_detection
41{
43{
44 WorldPtr old_world = world_.lock();
45 if (old_world)
46 old_world->removeObserver(observer_handle_);
47}
48
52
53WorldDiff::WorldDiff(const WorldPtr& world) : world_(world)
54{
55 observer_handle_ =
56 world->addObserver([this](const World::ObjectConstPtr& object, World::Action action) { notify(object, action); });
57}
58
60{
61 WorldPtr world = other.world_.lock();
62 if (world)
63 {
64 changes_ = other.changes_;
65
66 WorldWeakPtr(world).swap(world_);
67 observer_handle_ = world->addObserver(
68 [this](const World::ObjectConstPtr& object, World::Action action) { notify(object, action); });
69 }
70}
71
73{
75
76 WorldPtr old_world = world_.lock();
77 if (old_world)
78 old_world->removeObserver(observer_handle_);
79
80 world_.reset();
81}
82
83void WorldDiff::reset(const WorldPtr& world)
84{
86
87 WorldPtr old_world = world_.lock();
88 if (old_world)
89 old_world->removeObserver(observer_handle_);
90
91 WorldWeakPtr(world).swap(world_);
92 observer_handle_ =
93 world->addObserver([this](const World::ObjectConstPtr& object, World::Action action) { notify(object, action); });
94}
95
96void WorldDiff::setWorld(const WorldPtr& world)
97{
98 WorldPtr old_world = world_.lock();
99 if (old_world)
100 {
101 old_world->notifyObserverAllObjects(observer_handle_, World::DESTROY);
102 old_world->removeObserver(observer_handle_);
103 }
104
105 WorldWeakPtr(world).swap(world_);
106
107 observer_handle_ =
108 world->addObserver([this](const World::ObjectConstPtr& object, World::Action action) { notify(object, action); });
109 world->notifyObserverAllObjects(observer_handle_, World::CREATE | World::ADD_SHAPE);
110}
111
113{
114 changes_.clear();
115}
116
117void WorldDiff::notify(const World::ObjectConstPtr& obj, World::Action action)
118{
119 World::Action& a = changes_[obj->id_];
120 if (action == World::DESTROY)
121 {
123 }
124 else
125 {
126 a = a | action;
127 }
128}
129
130} // end of namespace collision_detection
Maintain a diff list of changes that have happened to a World.
Definition world_diff.h:48
void set(const std::string &id, World::Action val)
Definition world_diff.h:101
void setWorld(const WorldPtr &world)
Set which world to record. Records all objects in old world (if any) as DESTROYED and all objects in ...
void clearChanges()
Clear the internally maintained vector of changes.
void reset()
Turn off recording and erase all previously recorded changes.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition world.h:268