PathPlanner.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 RobotComponents::PathPlanner
17* @author Raphael Grimm ( raphael dot grimm at kit dot edu )
18* @date 2015 Humanoids Group, H2T, KIT
19* @license http://www.gnu.org/licenses/gpl-2.0.txt
20* GNU General Public License
21*/
22
23#include "PathPlanner.h"
24
25#include <VirtualRobot/CollisionDetection/CollisionChecker.h>
26#include <VirtualRobot/XML/RobotIO.h>
27
29
31#include <MemoryX/interface/memorytypes/MemoryEntities.h>
35
39
40void
42{
43 usingProxy(getProperty<std::string>("WorkingMemoryName").getValue());
44 // offeringTopic(getProperty<std::string>("DebugDrawerName").getValue());
45}
46
47void
49{
51 getProperty<std::string>("WorkingMemoryName").getValue());
52 commonStoragePrx = workingMemoryPrx->getCommonStorage();
54
55 // debugDrawer = getTopic<armarx::DebugDrawerInterfacePrx>(getProperty<std::string>("DebugDrawerName").getValue());
56}
57
58void
59armarx::PathPlanner::setCollisionObjects(const ::armarx::ObjectPositionBaseList& list,
60 const ::Ice::Current&)
61{
64}
65
66void
67armarx::PathPlanner::addCollisionObjects(const ::armarx::ObjectPositionBaseList& list,
68 const ::Ice::Current&)
69{
70 ARMARX_VERBOSE << "Adding " << list.size() << " collision objects";
71
72 //strong except guarantee
73 std::vector<CollisionObjectData> newObjects;
74
75 for (const auto& elem : list)
76 {
77 ARMARX_VERBOSE << "Object: " << newObjects.size();
78
79 CollisionObjectData newObject;
80 newObject.object = elem.objectClassBase;
81
82 ARMARX_VERBOSE << "Object: name " << newObject.object->getName() << ", id "
83 << newObject.object->getId();
84
85 memoryx::ObjectClassPtr objectClass =
86 memoryx::ObjectClassPtr::dynamicCast(elem.objectClassBase);
87
88 if (!objectClass)
89 {
90 std::stringstream s;
91 s << "Can't use object class with ice id " << elem.objectClassBase->ice_id();
92 ARMARX_ERROR_S << s.str();
93 throw armarx::InvalidArgumentException{s.str()};
94 }
95
96 ARMARX_VERBOSE << "Adding SimoxObjectWrapper";
98 objectClass->addWrapper(new memoryx::EntityWrappers::SimoxObjectWrapper(fileManager));
99 ARMARX_VERBOSE << "Getting ManipulationObject name and object";
100 VirtualRobot::ManipulationObjectPtr orgMo = sw->getManipulationObject();
101 std::string moName = orgMo->getName();
102 ARMARX_VERBOSE << "Cloning ManipulationObject";
103 VirtualRobot::ManipulationObjectPtr mo = orgMo->clone(moName);
104
105 ARMARX_VERBOSE << "Moving object";
106 //move the object to the given position
107 const auto objectPose = armarx::PosePtr::dynamicCast(elem.objectPose);
108
109 if (!objectPose)
110 {
111 std::stringstream s;
112 s << "Can't convert pose of " << objectClass->getName() << " to armarx::Pose.";
113 ARMARX_ERROR_S << s.str();
114 throw armarx::InvalidArgumentException{s.str()};
115 }
116
117 mo->setGlobalPose(objectPose->toEigen());
118
119 ARMARX_VERBOSE << "Get collision object";
120 VirtualRobot::CollisionModelPtr colModel = mo->getCollisionModel();
121
122 newObject.colModel = colModel;
123 newObjects.push_back(newObject);
124 ARMARX_VERBOSE << "Object: " << newObjects.size() - 1 << " done.";
125 }
126
127 //copy
128 std::copy(newObjects.begin(), newObjects.end(), std::back_inserter(objects));
129
130 ARMARX_VERBOSE << "Added " << newObjects.size()
131 << " collision objects. (Total: " << objects.size() << ")";
132}
133
134void
136{
137 ARMARX_VERBOSE << "Cleared " << objects.size() << " objects.";
138 objects.clear();
139}
140
141void
142armarx::PathPlanner::setAgent(const ::memoryx::AgentInstanceBasePtr& newAgent,
143 const std::string& agentColModelName,
144 const ::Ice::Current&)
145{
146 ARMARX_VERBOSE << "Setting agent '" << newAgent->getName() << "' with id " << newAgent->getId();
147 //get agent
148 std::string agentFilePath = newAgent->getAgentFilePath();
149
150 if (!ArmarXDataPath::getAbsolutePath(agentFilePath, agentFilePath))
151 {
152 ARMARX_ERROR << "Could not find robot file " << agentFilePath << std::flush;
153
154 ARMARX_VERBOSE << "Searched in " << ArmarXDataPath::getDataPaths().size()
155 << " additional paths";
156
157 for (const auto& path : ArmarXDataPath::getDataPaths())
158 {
159 ARMARX_VERBOSE << "\t" << path;
160 }
161
162 return;
163 }
164
165 //strong except guarantee
166 ARMARX_VERBOSE << "Loading agent: " << agentFilePath;
167 auto agent2 = VirtualRobot::RobotIO::loadRobot(agentFilePath, VirtualRobot::RobotIO::eFull);
168 ARMARX_VERBOSE << "Agent loaded.";
169
170 if (!agent2)
171 {
172 std::stringstream s;
173 s << "Can't load agent from: " << agentFilePath;
174 ARMARX_ERROR_S << s.str();
175 throw armarx::InvalidArgumentException{s.str()};
176 }
177
178 //get collision model
179 if (!agent2->hasRobotNode(agentColModelName) ||
180 !agent2->getRobotNode(agentColModelName)->getCollisionModel())
181 {
182 std::stringstream s;
183 s << "Agent has no collision model with name " << agentColModelName;
184 ARMARX_ERROR_S << s.str();
185 throw armarx::InvalidArgumentException{s.str()};
186 }
187
188 agent = agent2;
189 agentCollisionModel = agent->getRobotNode(agentColModelName)->getCollisionModel(); //->clone();
190 agentZCoord = agent->getGlobalPose()(2, 3);
191 ARMARX_VERBOSE << "Setting agent...done";
192}
193
194void
195armarx::PathPlanner::setSafetyMargin(::Ice::Float margin, const ::Ice::Current&)
196{
197 if (margin < 0)
198 {
199 std::stringstream s;
200 s << "Invalid margin: " << margin << " < 0.0";
201 ARMARX_ERROR_S << s.str();
202 throw armarx::InvalidArgumentException{s.str()};
203 }
204
205 safetyMargin = margin;
206}
207
208bool
210{
212 {
213 throw std::logic_error{"no agent collision model"};
214 }
215
216 if (objects.empty())
217 {
218 return true;
219 }
220
221 //set pose
222 Eigen::Matrix4f pose = Eigen::Matrix4f::Identity();
223 pose.block<3, 3>(0, 0) =
224 VirtualRobot::MathTools::axisangle2eigen3f(Eigen::Vector3f{0.f, 0.f, 1.f}, position.z);
225 pose(0, 3) = position.x;
226 pose(1, 3) = position.y;
227 pose(3, 3) = agentZCoord;
228 agent->setGlobalPose(pose);
229
230 if (safetyMargin > 0.01f)
231 {
232 for (const auto& object : objects)
233 {
234 float dist =
235 VirtualRobot::CollisionChecker::getGlobalCollisionChecker()->calculateDistance(
236 agentCollisionModel, object.colModel);
237
238 if (dist <= safetyMargin)
239 {
240 return false;
241 }
242 }
243 }
244 else
245 {
246 //the distance is small => only check collision
247 for (const auto& object : objects)
248 {
249 bool col = VirtualRobot::CollisionChecker::getGlobalCollisionChecker()->checkCollision(
250 agentCollisionModel, object.colModel);
251
252 if (col)
253 {
254 return false;
255 }
256 }
257 }
258
259 return true;
260}
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
static std::vector< std::string > getDataPaths()
Property< PropertyType > getProperty(const std::string &name)
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
void onInitComponent() override
memoryx::CommonStorageInterfacePrx commonStoragePrx
VirtualRobot::CollisionModelPtr agentCollisionModel
void setAgent(const ::memoryx::AgentInstanceBasePtr &newAgent, const std::string &agentColModelName, const ::Ice::Current &=Ice::emptyCurrent) override
memoryx::WorkingMemoryInterfacePrx workingMemoryPrx
void addCollisionObjects(const ::armarx::ObjectPositionBaseList &list, const ::Ice::Current &=Ice::emptyCurrent) override
bool isPositionValid(armarx::Vector3 position) const
void setCollisionObjects(const ::armarx::ObjectPositionBaseList &list, const ::Ice::Current &=Ice::emptyCurrent) override
memoryx::GridFileManagerPtr fileManager
void setSafetyMargin(::Ice::Float margin, const ::Ice::Current &=Ice::emptyCurrent) override
void onConnectComponent() override
void clearCollisionObjects(const ::Ice::Current &=Ice::emptyCurrent) override
std::vector< CollisionObjectData > objects
VirtualRobot::RobotPtr agent
The Vector3 class.
Definition Pose.h:113
SimoxObjectWrapper offers a simplified access to the Simox ManipulationObject (i.e visualization,...
GridFileManager provides utility functions for working with files in Mongo GridFS and links to them s...
#define ARMARX_ERROR_S
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:216
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
IceInternal::Handle< SimoxObjectWrapper > SimoxObjectWrapperPtr
IceInternal::Handle< ObjectClass > ObjectClassPtr
Definition ObjectClass.h:35
memoryx::ObjectClassBasePtr object
VirtualRobot::CollisionModelPtr colModel