collision_world.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/collision_detection/collision_world.h>
00038 #include <geometric_shapes/shape_operations.h>
00039 
00040 collision_detection::CollisionWorld::CollisionWorld() :
00041   world_(new World()),
00042   world_const_(world_)
00043 {
00044 }
00045 
00046 collision_detection::CollisionWorld::CollisionWorld(const WorldPtr& world) :
00047   world_(world),
00048   world_const_(world)
00049 {
00050 }
00051 
00052 collision_detection::CollisionWorld::CollisionWorld(const CollisionWorld &other, const WorldPtr& world) :
00053   world_(world),
00054   world_const_(world)
00055 {
00056 }
00057 
00058 void collision_detection::CollisionWorld::checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
00059 {
00060   robot.checkSelfCollision(req, res, state);
00061   if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
00062     checkRobotCollision(req, res, robot, state);
00063 }
00064 
00065 void collision_detection::CollisionWorld::checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
00066 {
00067   robot.checkSelfCollision(req, res, state, acm);
00068   if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
00069     checkRobotCollision(req, res, robot, state, acm);
00070 }
00071 
00072 void collision_detection::CollisionWorld::checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot,
00073                                                          const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
00074 {
00075   robot.checkSelfCollision(req, res, state1, state2);
00076   if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
00077     checkRobotCollision(req, res, robot, state1, state2);
00078 }
00079 
00080 void collision_detection::CollisionWorld::checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot,
00081                                                          const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
00082 {
00083   robot.checkSelfCollision(req, res, state1, state2, acm);
00084   if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
00085     checkRobotCollision(req, res, robot, state1, state2, acm);
00086 }
00087 
00088 void collision_detection::CollisionWorld::setWorld(const WorldPtr& world)
00089 {
00090   world_ = world;
00091   if (!world_)
00092     world_.reset(new World());
00093 
00094   world_const_ = world;
00095 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:46