hpp-pinocchio  6.0.0
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
collision-object.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016 CNRS
3 // Author: NMansard from Florent Lamiraux
4 //
5 //
6 
7 // Redistribution and use in source and binary forms, with or without
8 // modification, are permitted provided that the following conditions are
9 // met:
10 //
11 // 1. Redistributions of source code must retain the above copyright
12 // notice, this list of conditions and the following disclaimer.
13 //
14 // 2. Redistributions in binary form must reproduce the above copyright
15 // notice, this list of conditions and the following disclaimer in the
16 // documentation and/or other materials provided with the distribution.
17 //
18 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
21 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
22 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
24 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
26 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
29 // DAMAGE.
30 
31 #ifndef HPP_PINOCCHIO_COLLISION_OBJECT_HH
32 #define HPP_PINOCCHIO_COLLISION_OBJECT_HH
33 
34 #include <hpp/pinocchio/config.hh>
36 #include <hpp/pinocchio/fwd.hh>
37 #include <map>
38 #include <pinocchio/multibody/fwd.hpp>
39 
40 namespace pinocchio {
41 struct GeometryObject;
42 }
43 
44 namespace hpp {
45 namespace pinocchio {
47 
53  public:
54  typedef std::vector<GeomIndex> GeomIndexList;
55  typedef std::map<JointIndex, GeomIndexList> ObjectVec_t;
56 
58  CollisionObject(DevicePtr_t device, const GeomIndex geom);
59 
63  const GeomIndex geom);
64 
65  const std::string& name() const;
66 
68  const GeometryObject& pinocchio() const;
70 
73 
79 
85 
87  const JointIndex& jointIndex() const { return jointIndex_; }
88 
92 
95 
102  const Transform3s& getTransform() const;
103  const Transform3s& getTransform(const DeviceData& d) const;
104 
105  const GeomIndex& indexInModel() const { return geomInModelIndex; }
106 
111  void move(const Transform3s& position);
112 
113  protected:
115  void selfAssert() const;
116 
117  private:
118  GeomData& geomData() const;
119  GeomData& geomData(DeviceData& d) const;
120  const GeomData& geomData(const DeviceData& d) const;
121 
122  DevicePtr_t devicePtr;
123  GeomModelPtr_t geomModel_;
124  // If geomData_ is not null when the object is part of the environment.
125  // Otherwise, it is null.
126  GeomDataPtr_t geomData_;
127  JointIndex jointIndex_;
128  GeomIndex geomInModelIndex; // Index in global model list.
129 }; // class CollisionObject
130 } // namespace pinocchio
131 } // namespace hpp
132 
133 #endif // HPP_PINOCCHIO_COLLISION_OBJECT_HH
Definition: collision-object.hh:52
const Transform3s & getTransform(const DeviceData &d) const
CollisionObject(DevicePtr_t device, const GeomIndex geom)
Constructor for object of the device.
const std::string & name() const
const Transform3s & getTransform() const
const GeometryObject & pinocchio() const
Access to pinocchio object.
FclCollisionObjectPtr_t fcl(DeviceData &d) const
const Transform3s & positionInJointFrame() const
Return the position in the joint frame.
FclConstCollisionObjectPtr_t fcl(const DeviceData &d) const
void selfAssert() const
Assert that the members of the struct are valid (no null pointer, etc).
CollisionObject(GeomModelPtr_t geomModel, GeomDataPtr_t geomData, const GeomIndex geom)
JointPtr_t joint()
Get joint.
coal::Transform3s getFclTransform() const
std::map< JointIndex, GeomIndexList > ObjectVec_t
Definition: collision-object.hh:55
JointConstPtr_t joint() const
FclConstCollisionObjectPtr_t fcl(const GeomData &data) const
Access to coal object.
FclCollisionObjectPtr_t fcl(GeomData &data) const
CollisionGeometryPtr_t geometry() const
Access to coal object.
const GeomIndex & indexInModel() const
Definition: collision-object.hh:105
const JointIndex & jointIndex() const
Get joint index.
Definition: collision-object.hh:87
void move(const Transform3s &position)
FclConstCollisionObjectPtr_t fcl() const
FclCollisionObjectPtr_t fcl()
GeometryObject & pinocchio()
std::vector< GeomIndex > GeomIndexList
Definition: collision-object.hh:54
#define HPP_PINOCCHIO_DLLAPI
Definition: config.hh:88
shared_ptr< Device > DevicePtr_t
Definition: fwd.hh:118
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: fwd.hh:112
shared_ptr< Joint > JointPtr_t
Definition: fwd.hh:123
shared_ptr< GeomModel > GeomModelPtr_t
Definition: fwd.hh:133
::pinocchio::GeometryData GeomData
Definition: fwd.hh:80
::pinocchio::GeometryObject GeometryObject
Definition: collision-object.hh:46
shared_ptr< GeomData > GeomDataPtr_t
Definition: fwd.hh:135
::pinocchio::GeomIndex GeomIndex
Definition: fwd.hh:76
::pinocchio::SE3 Transform3s
Definition: fwd.hh:81
::pinocchio::JointIndex JointIndex
Definition: fwd.hh:74
shared_ptr< const Joint > JointConstPtr_t
Definition: fwd.hh:124
const coal::CollisionObject * FclConstCollisionObjectPtr_t
Definition: fwd.hh:115
coal::CollisionObject * FclCollisionObjectPtr_t
Definition: fwd.hh:114
Utility functions.
Definition: body.hh:39
Definition: collision-object.hh:40
Definition: device-data.hh:51