moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_robot_distance_field_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 the 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 
37 #pragma once
38 
39 #include <ros/ros.h>
41 #include <collision_distance_field/collision_robot_distance_field.h>
42 
43 namespace collision_detection
44 {
45 class CollisionRobotDistanceFieldROS : public CollisionRobotDistanceField
46 {
47 public:
48  CollisionRobotDistanceFieldROS(const planning_models::RobotModelConstPtr& robot_model, double size_x = DEFAULT_SIZE_X,
49  double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z,
50  bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
51  double resolution = DEFAULT_RESOLUTION,
52  double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
53  double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE,
54  double padding = 0.0, double scale = 1.0)
55  : CollisionRobotDistanceField(robot_model)
56  {
57  ros::NodeHandle nh;
58  std::map<std::string, std::vector<CollisionSphere> > coll_spheres;
59  collision_detection::loadLinkBodySphereDecompositions(nh, getRobotModel(), coll_spheres);
60  initialize(coll_spheres, size_x, size_y, size_z, use_signed_distance_field, resolution, collision_tolerance,
61  max_propogation_distance);
62  }
63 };
64 } // namespace collision_detection
CollisionRobotDistanceFieldROS(const planning_models::RobotModelConstPtr &robot_model, double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0)