hpp-core  6.0.0
Implement basic classes for canonical path planning for kinematic chains.
solid-solid-collision.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2014,2015,2016,2018 CNRS
3 // Authors: Florent Lamiraux, Joseph Mirabel, Diane Bury
4 //
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are
8 // met:
9 //
10 // 1. Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 //
13 // 2. Redistributions in binary form must reproduce the above copyright
14 // notice, this list of conditions and the following disclaimer in the
15 // documentation and/or other materials provided with the distribution.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
18 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
19 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
20 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
21 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
22 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
23 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
24 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
25 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
26 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
28 // DAMAGE.
29 
30 #ifndef HPP_CORE_CONTINUOUS_VALIDATION_SOLID_SOLID_COLLISION_HH
31 #define HPP_CORE_CONTINUOUS_VALIDATION_SOLID_SOLID_COLLISION_HH
32 
34 
35 namespace hpp {
36 namespace core {
37 namespace continuousValidation {
43 }; // struct CoefficientVelocity
44 typedef std::vector<CoefficientVelocity> CoefficientVelocities_t;
45 
56  public:
64  const JointPtr_t& joint_a, const ConstObjectStdVector_t& objects_b,
65  value_type tolerance);
66 
72  const JointPtr_t& joint_b,
73  value_type tolerance);
74 
77  const SolidSolidCollisionPtr_t& other);
78 
80 
82 
85  void breakDistance(value_type distance);
86 
87  std::string name() const;
88 
89  std::ostream& print(std::ostream& os) const;
90 
95  const CollisionObjectConstPtr_t& right);
96 
97  // Get coefficients and joints
99  return m_->coefficients;
100  }
101 
103  const JointPtr_t& joint_a() const { return m_->joint_a; }
105  const JointPtr_t& joint_b() const { return m_->joint_b; }
106 
109  return (m_->joint_a ? m_->joint_a->index() : 0);
110  }
113  return (m_->joint_b ? m_->joint_b->index() : 0);
114  }
115 
117 
118  protected:
124  SolidSolidCollision(const JointPtr_t& joint_a, const JointPtr_t& joint_b,
125  value_type tolerance);
126 
134  const ConstObjectStdVector_t& objects_b,
135  value_type tolerance);
136 
139  : BodyPairCollision(other), m_(other.m_) {}
140 
141  void init(const SolidSolidCollisionWkPtr_t& weak);
142 
143  private:
144  typedef pinocchio::JointIndex JointIndex;
145  typedef std::vector<JointIndex> JointIndices_t;
146 
147  struct Model {
148  JointPtr_t joint_a;
149  JointPtr_t joint_b;
150  CoefficientVelocities_t coefficients;
151  CoefficientVelocities_t coefficients_reverse;
152  JointIndices_t computeSequenceOfJoints() const;
153  CoefficientVelocities_t computeCoefficients(
154  const JointIndices_t& joints) const;
155  void setCoefficients(const JointIndices_t& joints);
156  };
157  shared_ptr<Model> m_;
158  SolidSolidCollisionWkPtr_t weak_;
159 }; // class SolidSolidCollision
160 } // namespace continuousValidation
161 } // namespace core
162 } // namespace hpp
163 #endif // HPP_CORE_CONTINUOUS_VALIDATION_SOLID_SOLID_COLLISION_HH
Definition: body-pair-collision.hh:62
Definition: solid-solid-collision.hh:55
SolidSolidCollision(const JointPtr_t &joint_a, const JointPtr_t &joint_b, value_type tolerance)
size_type indexJointA() const
Returns joint A index or -1 if no such joint exists.
Definition: solid-solid-collision.hh:108
const JointPtr_t & joint_a() const
Get joint a.
Definition: solid-solid-collision.hh:103
SolidSolidCollision(const JointPtr_t &joint_a, const ConstObjectStdVector_t &objects_b, value_type tolerance)
bool removeObjectTo_b(const CollisionObjectConstPtr_t &object)
static SolidSolidCollisionPtr_t createCopy(const SolidSolidCollisionPtr_t &other)
Copy instance and return shared pointer.
static SolidSolidCollisionPtr_t create(const JointPtr_t &joint_a, const JointPtr_t &joint_b, value_type tolerance)
void init(const SolidSolidCollisionWkPtr_t &weak)
static SolidSolidCollisionPtr_t create(const JointPtr_t &joint_a, const ConstObjectStdVector_t &objects_b, value_type tolerance)
value_type computeMaximalVelocity(vector_t &Vb) const
size_type indexJointB() const
Returns joint B index or -1 if no such joint exists.
Definition: solid-solid-collision.hh:112
void addCollisionPair(const CollisionObjectConstPtr_t &left, const CollisionObjectConstPtr_t &right)
const CoefficientVelocities_t & coefficients() const
Definition: solid-solid-collision.hh:98
const JointPtr_t & joint_b() const
Get joint b.
Definition: solid-solid-collision.hh:105
std::ostream & print(std::ostream &os) const
SolidSolidCollision(const SolidSolidCollision &other)
Copy constructor.
Definition: solid-solid-collision.hh:138
#define HPP_CORE_DLLAPI
Definition: config.hh:88
shared_ptr< IntervalValidation > IntervalValidationPtr_t
Definition: fwd.hh:261
std::vector< CoefficientVelocity > CoefficientVelocities_t
Definition: solid-solid-collision.hh:44
shared_ptr< SolidSolidCollision > SolidSolidCollisionPtr_t
Definition: fwd.hh:264
pinocchio::value_type value_type
Definition: fwd.hh:174
std::vector< CollisionObjectConstPtr_t > ConstObjectStdVector_t
Definition: fwd.hh:185
pinocchio::vector_t vector_t
Definition: fwd.hh:220
pinocchio::JointPtr_t JointPtr_t
Definition: fwd.hh:151
pinocchio::size_type size_type
Definition: fwd.hh:173
pinocchio::CollisionObjectConstPtr_t CollisionObjectConstPtr_t
Definition: fwd.hh:100
Definition: bi-rrt-planner.hh:35
Definition: solid-solid-collision.hh:38
JointPtr_t joint_
Joint the degrees of freedom of which the bounds correspond to.
Definition: solid-solid-collision.hh:41
CoefficientVelocity()
Definition: solid-solid-collision.hh:39
value_type value_
Definition: solid-solid-collision.hh:42