bodies.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 
35 /* Author: Ioan Sucan, E. Gil Jones */
36 
37 #ifndef GEOMETRIC_SHAPES_BODIES_
38 #define GEOMETRIC_SHAPES_BODIES_
39 
40 #if __cplusplus <= 199711L
41 #error This header requires at least C++11
42 #endif
43 
44 #include "geometric_shapes/aabb.h"
48 #include <Eigen/Core>
49 #include <Eigen/Geometry>
50 #include <memory>
51 #include <vector>
52 
57 namespace bodies
58 {
61 {
62  Eigen::Vector3d center;
63  double radius;
64 
65  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
66 };
67 
70 {
71  Eigen::Isometry3d pose;
72  double radius;
73  double length;
74  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
75 };
76 
77 class Body;
78 
80 typedef std::shared_ptr<Body> BodyPtr;
81 
83 typedef std::shared_ptr<const Body> BodyConstPtr;
84 
88 class Body
89 {
90 public:
91  Body() : scale_(1.0), padding_(0.0), type_(shapes::UNKNOWN_SHAPE)
92  {
93  pose_.setIdentity();
94  }
95 
96  virtual ~Body()
97  {
98  }
99 
102  {
103  return type_;
104  }
105 
114  void setScaleDirty(double scale)
115  {
116  scale_ = scale;
117  }
118 
121  void setScale(double scale)
122  {
123  setScaleDirty(scale);
124  updateInternalData();
125  }
126 
128  double getScale() const
129  {
130  return scale_;
131  }
132 
141  void setPaddingDirty(double padd)
142  {
143  padding_ = padd;
144  }
145 
148  void setPadding(double padd)
149  {
150  setPaddingDirty(padd);
151  updateInternalData();
152  }
153 
155  double getPadding() const
156  {
157  return padding_;
158  }
159 
168  void setPoseDirty(const Eigen::Isometry3d& pose)
169  {
170  pose_ = pose;
171  }
172 
174  void setPose(const Eigen::Isometry3d& pose)
175  {
176  setPoseDirty(pose);
177  updateInternalData();
178  }
179 
181  const Eigen::Isometry3d& getPose() const
182  {
183  return pose_;
184  }
185 
194  inline void setDimensionsDirty(const shapes::Shape* shape)
195  {
196  useDimensions(shape);
197  }
198 
200  virtual std::vector<double> getDimensions() const = 0;
201 
203  void setDimensions(const shapes::Shape* shape);
204 
206  bool containsPoint(double x, double y, double z, bool verbose = false) const
207  {
208  Eigen::Vector3d pt(x, y, z);
209  return containsPoint(pt, verbose);
210  }
211 
213  virtual bool containsPoint(const Eigen::Vector3d& p, bool verbose = false) const = 0;
214 
220  virtual bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
221  EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const = 0;
222 
225  virtual double computeVolume() const = 0;
226 
232  virtual bool samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
233  Eigen::Vector3d& result) const;
234 
237  virtual void computeBoundingSphere(BoundingSphere& sphere) const = 0;
238 
241  virtual void computeBoundingCylinder(BoundingCylinder& cylinder) const = 0;
242 
245  virtual void computeBoundingBox(AABB& bbox) const = 0;
246 
248  BodyPtr cloneAt(const Eigen::Isometry3d& pose) const
249  {
250  return cloneAt(pose, padding_, scale_);
251  }
252 
257  virtual BodyPtr cloneAt(const Eigen::Isometry3d& pose, double padding, double scaling) const = 0;
258 
262  virtual void updateInternalData() = 0;
263 
264 protected:
266  virtual void useDimensions(const shapes::Shape* shape) = 0;
267 
269  double scale_;
270 
272  double padding_;
273 
276 
278  Eigen::Isometry3d pose_;
279 
280 public:
281  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
282 };
283 
285 class Sphere : public Body
286 {
287 public:
288  Sphere() : Body()
289  {
290  type_ = shapes::SPHERE;
291  }
292 
293  Sphere(const shapes::Shape* shape) : Body()
294  {
295  type_ = shapes::SPHERE;
296  setDimensions(shape);
297  }
298 
299  explicit Sphere(const BoundingSphere& sphere) : Body()
300  {
301  type_ = shapes::SPHERE;
302  shapes::Sphere shape(sphere.radius);
303  setDimensionsDirty(&shape);
304 
305  Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
306  pose.translation() = sphere.center;
307  setPose(pose);
308  }
309 
310  ~Sphere() override
311  {
312  }
313 
315  std::vector<double> getDimensions() const override;
316 
317  bool containsPoint(const Eigen::Vector3d& p, bool verbose = false) const override;
318  double computeVolume() const override;
319  bool samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
320  Eigen::Vector3d& result) const override;
321  void computeBoundingSphere(BoundingSphere& sphere) const override;
322  void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
323  void computeBoundingBox(AABB& bbox) const override;
324  bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
325  EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
326 
327  BodyPtr cloneAt(const Eigen::Isometry3d& pose, double padding, double scale) const override;
328 
329  void updateInternalData() override;
330 
331 protected:
332  void useDimensions(const shapes::Shape* shape) override;
333 
334  // shape-dependent data
335  double radius_;
336 
337  // pose/padding/scaling-dependent values & values computed for convenience and fast upcoming computations
338  Eigen::Vector3d center_;
339  double radiusU_;
340  double radius2_;
341 
342 public:
343  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
344 };
345 
347 class Cylinder : public Body
348 {
349 public:
351  {
352  type_ = shapes::CYLINDER;
353  }
354 
355  Cylinder(const shapes::Shape* shape) : Body()
356  {
357  type_ = shapes::CYLINDER;
358  setDimensions(shape);
359  }
360 
361  explicit Cylinder(const BoundingCylinder& cylinder) : Body()
362  {
363  type_ = shapes::CYLINDER;
364  shapes::Cylinder shape(cylinder.radius, cylinder.length);
365  setDimensionsDirty(&shape);
366  setPose(cylinder.pose);
367  }
368 
369  ~Cylinder() override
370  {
371  }
372 
374  std::vector<double> getDimensions() const override;
375 
376  bool containsPoint(const Eigen::Vector3d& p, bool verbose = false) const override;
377  double computeVolume() const override;
378  bool samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
379  Eigen::Vector3d& result) const override;
380  void computeBoundingSphere(BoundingSphere& sphere) const override;
381  void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
382  void computeBoundingBox(AABB& bbox) const override;
383  bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
384  EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
385 
386  BodyPtr cloneAt(const Eigen::Isometry3d& pose, double padding, double scale) const override;
387 
388  void updateInternalData() override;
389 
390 protected:
391  void useDimensions(const shapes::Shape* shape) override;
392 
393  // shape-dependent data
394  double length_;
395  double radius_;
396 
397  // pose/padding/scaling-dependent values & values computed for convenience and fast upcoming computations
398  Eigen::Vector3d center_;
399  Eigen::Vector3d normalH_;
400  Eigen::Vector3d normalB1_;
401  Eigen::Vector3d normalB2_;
402 
403  double length2_;
404  double radiusU_;
405  double radiusB_;
406  double radiusBSqr_;
407  double radius2_;
408  double d1_;
409  double d2_;
410 
411 public:
412  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
413 };
414 
416 class Box : public Body
417 {
418 public:
419  Box() : Body()
420  {
421  type_ = shapes::BOX;
422  }
423 
424  Box(const shapes::Shape* shape) : Body()
425  {
426  type_ = shapes::BOX;
427  setDimensions(shape);
428  }
429 
430  explicit Box(const AABB& aabb) : Body()
431  {
432  type_ = shapes::BOX;
433  shapes::Box shape(aabb.sizes()[0], aabb.sizes()[1], aabb.sizes()[2]);
434  setDimensionsDirty(&shape);
435 
436  Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
437  pose.translation() = aabb.center();
438  setPose(pose);
439  }
440 
441  ~Box() override
442  {
443  }
444 
446  std::vector<double> getDimensions() const override;
447 
448  bool containsPoint(const Eigen::Vector3d& p, bool verbose = false) const override;
449  double computeVolume() const override;
450  bool samplePointInside(random_numbers::RandomNumberGenerator& rng, unsigned int max_attempts,
451  Eigen::Vector3d& result) const override;
452  void computeBoundingSphere(BoundingSphere& sphere) const override;
453  void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
454  void computeBoundingBox(AABB& bbox) const override;
455  bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
456  EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
457 
458  BodyPtr cloneAt(const Eigen::Isometry3d& pose, double padding, double scale) const override;
459 
460  void updateInternalData() override;
461 
462 protected:
463  void useDimensions(const shapes::Shape* shape) override; // (x, y, z) = (length, width, height)
464 
465  // shape-dependent data
466  double length_;
467  double width_;
468  double height_;
469 
470  // pose/padding/scaling-dependent values & values computed for convenience and fast upcoming computations
471  Eigen::Vector3d center_;
472  Eigen::Vector3d normalL_;
473  Eigen::Vector3d normalW_;
474  Eigen::Vector3d normalH_;
475 
476  Eigen::Vector3d corner1_;
477  Eigen::Vector3d corner2_;
478 
479  double length2_;
480  double width2_;
481  double height2_;
482  double radiusB_;
483  double radius2_;
484 
485 public:
486  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
487 };
488 
490 class ConvexMesh : public Body
491 {
492 public:
494  {
495  type_ = shapes::MESH;
496  scaled_vertices_ = nullptr;
497  }
498 
499  ConvexMesh(const shapes::Shape* shape) : Body()
500  {
501  type_ = shapes::MESH;
502  scaled_vertices_ = nullptr;
503  setDimensions(shape);
504  }
505 
506  ~ConvexMesh() override;
507 
509  std::vector<double> getDimensions() const override;
510 
511  bool containsPoint(const Eigen::Vector3d& p, bool verbose = false) const override;
512  double computeVolume() const override;
513 
514  void computeBoundingSphere(BoundingSphere& sphere) const override;
515  void computeBoundingCylinder(BoundingCylinder& cylinder) const override;
516  void computeBoundingBox(AABB& bbox) const override;
517  bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir,
518  EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const override;
519 
520  const std::vector<unsigned int>& getTriangles() const;
521  const EigenSTL::vector_Vector3d& getVertices() const;
522  const EigenSTL::vector_Vector3d& getScaledVertices() const;
523 
528  const EigenSTL::vector_Vector4d& getPlanes() const;
529 
530  BodyPtr cloneAt(const Eigen::Isometry3d& pose, double padding, double scale) const override;
531 
533  void computeScaledVerticesFromPlaneProjections();
534 
535  void correctVertexOrderFromPlanes();
536 
537  void updateInternalData() override;
538 
539 protected:
540  void useDimensions(const shapes::Shape* shape) override;
541 
543  unsigned int countVerticesBehindPlane(const Eigen::Vector4f& planeNormal) const;
544 
551  bool isPointInsidePlanes(const Eigen::Vector3d& point) const;
552 
553  struct MeshData
554  {
557  std::vector<unsigned int> triangles_;
558  std::map<unsigned int, unsigned int> plane_for_triangle_;
559  Eigen::Vector3d mesh_center_;
561  Eigen::Vector3d box_offset_;
562  Eigen::Vector3d box_size_;
564 
565  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
566  };
567 
568  // shape-dependent data; keep this in one struct so that a cheap pointer copy can be done in cloneAt()
569  std::shared_ptr<MeshData> mesh_data_;
570 
571  // pose/padding/scaling-dependent values & values computed for convenience and fast upcoming computations
572  Eigen::Isometry3d i_pose_;
573  Eigen::Vector3d center_;
574  double radiusB_;
575  double radiusBSqr_;
577 
578  // pointer to an array of scaled vertices
579  // If the padding is 0 & scaling is 1, then there is no need to have scaled vertices;
580  // we can just point to the vertices in mesh_data_.
581  // Otherwise, point to scaled_vertices_storage_
583 
584 private:
585  std::unique_ptr<EigenSTL::vector_Vector3d> scaled_vertices_storage_;
586 
587 public:
588  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
589 };
590 
595 {
596 public:
597  BodyVector();
598 
600  BodyVector(const std::vector<shapes::Shape*>& shapes, const EigenSTL::vector_Isometry3d& poses, double padding = 0.0);
601 
602  ~BodyVector();
603 
605  void addBody(Body* body);
606 
608  void addBody(const shapes::Shape* shape, const Eigen::Isometry3d& pose, double padding = 0.0);
609 
611  void clear();
612 
614  void setPose(unsigned int i, const Eigen::Isometry3d& pose);
615 
617  std::size_t getCount() const;
618 
620  bool containsPoint(const Eigen::Vector3d& p, bool verbose = false) const;
621 
623  bool containsPoint(const Eigen::Vector3d& p, std::size_t& index, bool verbose = false) const;
624 
630  bool intersectsRay(const Eigen::Vector3d& origin, const Eigen::Vector3d& dir, std::size_t& index,
631  EigenSTL::vector_Vector3d* intersections = nullptr, unsigned int count = 0) const;
632 
634  const Body* getBody(unsigned int i) const;
635 
636 private:
637  std::vector<Body*> bodies_;
638 };
639 
641 typedef std::shared_ptr<Body> BodyPtr;
642 
644 typedef std::shared_ptr<const Body> BodyConstPtr;
645 } // namespace bodies
646 
647 #endif
double radiusBSqr_
Definition: bodies.h:575
Definition of various shapes. No properties such as position are included. These are simply the descr...
Eigen::Vector3d normalH_
Definition: bodies.h:474
std::vector< unsigned int > triangles_
Definition: bodies.h:557
double radius2_
Definition: bodies.h:340
void setDimensionsDirty(const shapes::Shape *shape)
Set the dimensions of the body (from corresponding shape).
Definition: bodies.h:194
void setScaleDirty(double scale)
If the dimension of the body should be scaled, this method sets the scale.
Definition: bodies.h:114
void setPose(const Eigen::Isometry3d &pose)
Set the pose of the body. Default is identity.
Definition: bodies.h:174
void computeBoundingSphere(const std::vector< const Body *> &bodies, BoundingSphere &mergedSphere)
Compute the bounding sphere for a set of bodies and store the resulting sphere in mergedSphere...
Eigen::Vector3d corner2_
The translated, but not rotated max corner.
Definition: bodies.h:477
Eigen::Vector3d center_
Definition: bodies.h:471
Eigen::Vector3d normalL_
Definition: bodies.h:472
Definition of a cylinder Length is along z axis. Origin is at center of mass.
Definition: shapes.h:127
double width2_
Definition: bodies.h:480
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
bool containsPoint(double x, double y, double z, bool verbose=false) const
Check if a point is inside the body.
Definition: bodies.h:206
Definition of a cylinder.
Definition: bodies.h:347
EigenSTL::vector_Vector3d vertices_
Definition: bodies.h:556
double radiusB_
Definition: bodies.h:482
double radius2_
Definition: bodies.h:483
std::map< unsigned int, unsigned int > plane_for_triangle_
Definition: bodies.h:558
std::shared_ptr< Body > BodyPtr
Shared pointer to a Body.
Definition: bodies.h:77
Definition of a sphere.
Definition: bodies.h:285
double radius_
Definition: bodies.h:335
virtual ~Body()
Definition: bodies.h:96
std::shared_ptr< MeshData > mesh_data_
Definition: bodies.h:569
std::vector< Body * > bodies_
Definition: bodies.h:637
Box(const shapes::Shape *shape)
Definition: bodies.h:424
Eigen::Vector3d normalW_
Definition: bodies.h:473
Eigen::Vector3d mesh_center_
Definition: bodies.h:559
void setScale(double scale)
If the dimension of the body should be scaled, this method sets the scale. Default is 1...
Definition: bodies.h:121
double radiusBSqr_
Definition: bodies.h:406
double length_
Definition: bodies.h:394
Eigen::Vector3d center
Definition: bodies.h:62
Eigen::Isometry3d pose_
The location of the body (position and orientation)
Definition: bodies.h:278
double length2_
Definition: bodies.h:479
double y
Eigen::Vector3d center_
Definition: bodies.h:338
Definition of a sphere that bounds another object.
Definition: bodies.h:60
double radiusU_
Definition: bodies.h:404
Eigen::Vector3d box_size_
Definition: bodies.h:562
shapes::ShapeType type_
The type of shape this body was constructed from.
Definition: bodies.h:275
double radiusB_
Definition: bodies.h:405
std::shared_ptr< const Body > BodyConstPtr
Shared pointer to a const Body.
Definition: bodies.h:83
double width_
Definition: bodies.h:467
double height2_
Definition: bodies.h:481
unsigned int index
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:77
double radiusU_
Definition: bodies.h:339
Definition of a convex mesh. Convex hull is computed for a given shape::Mesh.
Definition: bodies.h:490
Eigen::Vector3d normalB1_
Definition: bodies.h:400
~Box() override
Definition: bodies.h:441
Definition of a box.
Definition: bodies.h:416
Definition of a cylinder.
Definition: bodies.h:69
EigenSTL::vector_Vector3d * scaled_vertices_
Definition: bodies.h:582
BoundingCylinder bounding_cylinder_
Definition: bodies.h:563
double radius2_
Definition: bodies.h:407
double length2_
Definition: bodies.h:403
Cylinder(const BoundingCylinder &cylinder)
Definition: bodies.h:361
double z
ShapeType
A list of known shape types.
Definition: shapes.h:61
double padding_
The scale that was set for this body.
Definition: bodies.h:272
double height_
Definition: bodies.h:468
Eigen::Vector3d center_
Definition: bodies.h:398
BodyPtr cloneAt(const Eigen::Isometry3d &pose) const
Get a clone of this body, but one that is located at the pose pose.
Definition: bodies.h:248
std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > vector_Vector4d
EigenSTL::vector_Vector4d planes_
Definition: bodies.h:555
Definition of a sphere.
Definition: shapes.h:106
~Sphere() override
Definition: bodies.h:310
A vector of Body objects.
Definition: bodies.h:594
void setPaddingDirty(double padd)
If the dimension of the body should be padded, this method sets the pading.
Definition: bodies.h:141
std::unique_ptr< EigenSTL::vector_Vector3d > scaled_vertices_storage_
Definition: bodies.h:585
double getScale() const
Retrieve the current scale.
Definition: bodies.h:128
Eigen::Vector3d center_
Definition: bodies.h:573
double d1_
Definition: bodies.h:408
double getPadding() const
Retrieve the current padding.
Definition: bodies.h:155
Eigen::Vector3d normalH_
Definition: bodies.h:399
Eigen::Vector3d normalB2_
Definition: bodies.h:401
Cylinder(const shapes::Shape *shape)
Definition: bodies.h:355
Eigen::Isometry3d pose
Definition: bodies.h:71
Definition of a box Aligned with the XYZ axes.
Definition: shapes.h:226
Box(const AABB &aabb)
Definition: bodies.h:430
ConvexMesh(const shapes::Shape *shape)
Definition: bodies.h:499
Eigen::Vector3d corner1_
The translated, but not rotated min corner.
Definition: bodies.h:476
void setPoseDirty(const Eigen::Isometry3d &pose)
Set the pose of the body.
Definition: bodies.h:168
double radius_
Definition: bodies.h:395
Sphere(const shapes::Shape *shape)
Definition: bodies.h:293
Eigen::Vector3d box_offset_
Definition: bodies.h:561
Represents an axis-aligned bounding box.
Definition: aabb.h:45
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
~Cylinder() override
Definition: bodies.h:369
const Eigen::Isometry3d & getPose() const
Retrieve the pose of the body.
Definition: bodies.h:181
shapes::ShapeType getType() const
Get the type of shape this body represents.
Definition: bodies.h:101
double d2_
Definition: bodies.h:409
double length_
Definition: bodies.h:466
double x
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
Definition: bodies.h:88
double radiusB_
Definition: bodies.h:574
Eigen::Isometry3d i_pose_
Definition: bodies.h:572
void setPadding(double padd)
If constant padding should be added to the body, this method sets the padding. Default is 0...
Definition: bodies.h:148
double scale_
The scale that was set for this body.
Definition: bodies.h:269
Sphere(const BoundingSphere &sphere)
Definition: bodies.h:299
This set of classes allows quickly detecting whether a given point is inside an object or not...
Definition: aabb.h:42


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Tue May 26 2020 03:13:02