diff --git a/include/hpp/fcl/collision_data.h b/include/hpp/fcl/collision_data.h
index 9eb4bc81e4238b38cb86ba9fbce4a39d86dab9ae..9516b4cb6dbb92649f3a84f61a3fb7b2fa3a8bae 100644
--- a/include/hpp/fcl/collision_data.h
+++ b/include/hpp/fcl/collision_data.h
@@ -444,8 +444,9 @@ struct HPP_FCL_DLLAPI CollisionResult : QueryResult {
   /// @brief get the i-th contact calculated
   const Contact& getContact(size_t i) const {
     if (contacts.size() == 0)
-      throw std::invalid_argument(
-          "The number of contacts is zero. No Contact can be returned.");
+      HPP_FCL_THROW_PRETTY(
+          "The number of contacts is zero. No Contact can be returned.",
+          std::invalid_argument);
 
     if (i < contacts.size())
       return contacts[i];
@@ -456,8 +457,9 @@ struct HPP_FCL_DLLAPI CollisionResult : QueryResult {
   /// @brief set the i-th contact calculated
   void setContact(size_t i, const Contact& c) {
     if (contacts.size() == 0)
-      throw std::invalid_argument(
-          "The number of contacts is zero. No Contact can be returned.");
+      HPP_FCL_THROW_PRETTY(
+          "The number of contacts is zero. No Contact can be returned.",
+          std::invalid_argument);
 
     if (i < contacts.size())
       contacts[i] = c;
diff --git a/include/hpp/fcl/narrowphase/narrowphase.h b/include/hpp/fcl/narrowphase/narrowphase.h
index bd4a27f25f63295dd7ad40076c765b7a157c9b13..daa72bf5661a0141d68b279a671134eb9c370448 100644
--- a/include/hpp/fcl/narrowphase/narrowphase.h
+++ b/include/hpp/fcl/narrowphase/narrowphase.h
@@ -263,7 +263,8 @@ struct HPP_FCL_DLLAPI GJKSolver {
         break;
       default:
         assert(false && "should not reach type part.");
-        throw std::logic_error("GJKSolver: should not reach this part.");
+        HPP_FCL_THROW_PRETTY("GJKSolver: should not reach this part.",
+                             std::logic_error)
     }
     return col;
   }
diff --git a/include/hpp/fcl/serialization/BVH_model.h b/include/hpp/fcl/serialization/BVH_model.h
index 3b2a7eca2d879bb655b72f535a04110b58e1f6f8..ef29fe7bef0db5cf1a87c98bbd2f55cf090a6ff7 100644
--- a/include/hpp/fcl/serialization/BVH_model.h
+++ b/include/hpp/fcl/serialization/BVH_model.h
@@ -32,10 +32,11 @@ void save(Archive &ar, const hpp::fcl::BVHModelBase &bvh_model,
   if (!(bvh_model.build_state == BVH_BUILD_STATE_PROCESSED ||
         bvh_model.build_state == BVH_BUILD_STATE_UPDATED) &&
       (bvh_model.getModelType() == BVH_MODEL_TRIANGLES)) {
-    throw std::invalid_argument(
+    HPP_FCL_THROW_PRETTY(
         "The BVH model is not in a BVH_BUILD_STATE_PROCESSED or "
         "BVH_BUILD_STATE_UPDATED state.\n"
-        "The BVHModel could not be serialized.");
+        "The BVHModel could not be serialized.",
+        std::invalid_argument);
   }
 
   ar &make_nvp("base",
diff --git a/src/broadphase/broadphase_dynamic_AABB_tree.cpp b/src/broadphase/broadphase_dynamic_AABB_tree.cpp
index 6d8c78f4720b29dea532761dbe6b719aca9a8f0b..9338cc42434d704194f8028f65c48f0d2c60da73 100644
--- a/src/broadphase/broadphase_dynamic_AABB_tree.cpp
+++ b/src/broadphase/broadphase_dynamic_AABB_tree.cpp
@@ -515,7 +515,8 @@ void DynamicAABBTreeCollisionManager::update() {
     DynamicAABBNode* node = it->second;
     node->bv = obj->getAABB();
     if (node->bv.volume() <= 0.)
-      throw std::invalid_argument("The bounding volume has a negative volume.");
+      HPP_FCL_THROW_PRETTY("The bounding volume has a negative volume.",
+                           std::invalid_argument)
   }
 
   dtree.refit();
diff --git a/src/collision_utility.cpp b/src/collision_utility.cpp
index 586f6f6352376124a8bf73a91561bf6c38900b3d..05fd42969192210617b974b995175a0c970f276b 100644
--- a/src/collision_utility.cpp
+++ b/src/collision_utility.cpp
@@ -60,7 +60,8 @@ CollisionGeometry* extractBVH(const CollisionGeometry* model,
     case BV_KDOP24:
       return extractBVHtpl<KDOP<24> >(model, pose, aabb);
     default:
-      throw std::runtime_error("Unknown type of bounding volume");
+      HPP_FCL_THROW_PRETTY("Unknown type of bounding volume",
+                           std::runtime_error);
   }
 }
 }  // namespace details
@@ -72,8 +73,9 @@ CollisionGeometry* extract(const CollisionGeometry* model,
       return details::extractBVH(model, pose, aabb);
     // case OT_GEOM: return model;
     default:
-      throw std::runtime_error(
-          "Extraction is not implemented for this type of object");
+      HPP_FCL_THROW_PRETTY(
+          "Extraction is not implemented for this type of object",
+          std::runtime_error);
   }
 }
 }  // namespace fcl
diff --git a/src/mesh_loader/assimp.cpp b/src/mesh_loader/assimp.cpp
index 634beba1f5c6973729ed8856a489896d3f75ad36..495ace6024066c5cc3cdc535d0b60242c4dd5036 100644
--- a/src/mesh_loader/assimp.cpp
+++ b/src/mesh_loader/assimp.cpp
@@ -89,12 +89,13 @@ void Loader::load(const std::string& resource_path) {
         std::string("Could not load resource ") + resource_path +
         std::string("\n") + importer->GetErrorString() + std::string("\n") +
         "Hint: the mesh directory may be wrong.");
-    throw std::invalid_argument(exception_message);
+    HPP_FCL_THROW_PRETTY(exception_message.c_str(), std::invalid_argument);
   }
 
   if (!scene->HasMeshes())
-    throw std::invalid_argument(std::string("No meshes found in file ") +
-                                resource_path);
+    HPP_FCL_THROW_PRETTY(
+        (std::string("No meshes found in file ") + resource_path).c_str(),
+        std::invalid_argument);
 }
 
 /**
diff --git a/src/mesh_loader/loader.cpp b/src/mesh_loader/loader.cpp
index b874c54eca7d8d256e190eca0c1e592b01a2f418..4c2f7f418fd42834bb2e69bd7bf1b4936f1ed9fc 100644
--- a/src/mesh_loader/loader.cpp
+++ b/src/mesh_loader/loader.cpp
@@ -83,7 +83,8 @@ BVHModelPtr_t MeshLoader::load(const std::string& filename,
     case BV_KDOP24:
       return _load<KDOP<24> >(filename, scale);
     default:
-      throw std::invalid_argument("Unhandled bouding volume type.");
+      HPP_FCL_THROW_PRETTY("Unhandled bouding volume type.",
+                           std::invalid_argument);
   }
 }
 
@@ -92,8 +93,9 @@ CollisionGeometryPtr_t MeshLoader::loadOctree(const std::string& filename) {
   shared_ptr<octomap::OcTree> octree(new octomap::OcTree(filename));
   return CollisionGeometryPtr_t(new hpp::fcl::OcTree(octree));
 #else
-  throw std::logic_error(
-      "hpp-fcl compiled without OctoMap. Cannot create OcTrees.");
+  HPP_FCL_THROW_PRETTY(
+      "hpp-fcl compiled without OctoMap. Cannot create OcTrees.",
+      std::logic_error);
 #endif
 }
 
diff --git a/src/narrowphase/gjk.cpp b/src/narrowphase/gjk.cpp
index b24d5d560d49041b9bd3cc3e0e3cb9edbd7ff2ce..c40fd5364b21795ad42bb48e2af0351869a31962 100644
--- a/src/narrowphase/gjk.cpp
+++ b/src/narrowphase/gjk.cpp
@@ -402,7 +402,7 @@ MinkowskiDiff::GetSupportFunction makeGetSupportFunction1(
           return getSupportFuncTpl<Shape0, SmallConvex, false>;
       }
     default:
-      throw std::logic_error("Unsupported geometric shape");
+      HPP_FCL_THROW_PRETTY("Unsupported geometric shape.", std::logic_error);
   }
 }
 
@@ -451,7 +451,7 @@ MinkowskiDiff::GetSupportFunction makeGetSupportFunction0(
             s1, identity, inflation, linear_log_convex_threshold);
       break;
     default:
-      throw std::logic_error("Unsupported geometric shape");
+      HPP_FCL_THROW_PRETTY("Unsupported geometric shape", std::logic_error);
   }
 }
 
@@ -482,7 +482,7 @@ bool getNormalizeSupportDirection(const ShapeBase* shape) {
       return (bool)shape_traits<ConvexBase>::NeedNesterovNormalizeHeuristic;
       break;
     default:
-      throw std::logic_error("Unsupported geometric shape");
+      HPP_FCL_THROW_PRETTY("Unsupported geometric shape", std::logic_error);
   }
 }
 
@@ -586,7 +586,8 @@ bool getClosestPoints(const GJK::Simplex& simplex, Vec3f& w0, Vec3f& w1) {
                                                     vs[2]->w, vs[3]->w);
       break;
     default:
-      throw std::logic_error("The simplex rank must be in [ 1, 4 ]");
+      HPP_FCL_THROW_PRETTY("The simplex rank must be in [ 1, 4 ]",
+                           std::logic_error);
   }
   w0.setZero();
   w1.setZero();
@@ -719,7 +720,7 @@ GJK::Status GJK::evaluate(const MinkowskiDiff& shape_, const Vec3f& guess,
         break;
 
       default:
-        throw std::logic_error("Invalid momentum variant.");
+        HPP_FCL_THROW_PRETTY("Invalid momentum variant.", std::logic_error);
     }
 
     appendVertex(curr_simplex, -dir, false,
@@ -789,7 +790,7 @@ GJK::Status GJK::evaluate(const MinkowskiDiff& shape_, const Vec3f& guess,
         inside = projectTetrahedraOrigin(curr_simplex, next_simplex);
         break;
       default:
-        throw std::logic_error("Invalid simplex rank");
+        HPP_FCL_THROW_PRETTY("Invalid simplex rank", std::logic_error);
     }
     assert(nfree + next_simplex.rank == 4);
     current = next;
@@ -826,13 +827,15 @@ bool GJK::checkConvergence(const Vec3f& w, const FCL_REAL& rl, FCL_REAL& alpha,
       diff = rl - alpha;
       switch (convergence_criterion_type) {
         case Absolute:
-          throw std::logic_error("VDB convergence criterion is relative.");
+          HPP_FCL_THROW_PRETTY("VDB convergence criterion is relative.",
+                               std::logic_error);
           break;
         case Relative:
           check_passed = (diff - tolerance * rl) <= 0;
           break;
         default:
-          throw std::logic_error("Invalid convergence criterion type.");
+          HPP_FCL_THROW_PRETTY("Invalid convergence criterion type.",
+                               std::logic_error);
       }
       break;
 
@@ -847,7 +850,8 @@ bool GJK::checkConvergence(const Vec3f& w, const FCL_REAL& rl, FCL_REAL& alpha,
           check_passed = ((diff / tolerance * rl) - tolerance * rl) <= 0;
           break;
         default:
-          throw std::logic_error("Invalid convergence criterion type.");
+          HPP_FCL_THROW_PRETTY("Invalid convergence criterion type.",
+                               std::logic_error);
       }
       break;
 
@@ -864,12 +868,13 @@ bool GJK::checkConvergence(const Vec3f& w, const FCL_REAL& rl, FCL_REAL& alpha,
           check_passed = ((diff / tolerance * rl) - tolerance * rl) <= 0;
           break;
         default:
-          throw std::logic_error("Invalid convergence criterion type.");
+          HPP_FCL_THROW_PRETTY("Invalid convergence criterion type.",
+                               std::logic_error);
       }
       break;
 
     default:
-      throw std::logic_error("Invalid convergence criterion.");
+      HPP_FCL_THROW_PRETTY("Invalid convergence criterion.", std::logic_error);
   }
   return check_passed;
 }
diff --git a/src/octree.cpp b/src/octree.cpp
index 0b661d8188cc87933d078161445b1c5b27ea6622..7e01605965be4e3df605a279c89df4c4f124f1f2 100644
--- a/src/octree.cpp
+++ b/src/octree.cpp
@@ -166,8 +166,10 @@ void OcTree::exportAsObjFile(const std::string& filename) const {
   std::ofstream os;
   os.open(filename);
   if (!os.is_open())
-    throw std::runtime_error(std::string("failed to open file \"") + filename +
-                             std::string("\""));
+    HPP_FCL_THROW_PRETTY(
+        (std::string("failed to open file \"") + filename + std::string("\""))
+            .c_str(),
+        std::runtime_error);
   // write vertices
   os << "# list of vertices\n";
   for (VectorVec3f::const_iterator it = vertices.begin(); it != vertices.end();
diff --git a/src/shape/convex.cpp b/src/shape/convex.cpp
index bd1de134a7f3ac768141ce4f33706ee2368674bb..c50d1e7c6e9e6569d3c3649e5643642abd3d0bd7 100644
--- a/src/shape/convex.cpp
+++ b/src/shape/convex.cpp
@@ -57,9 +57,10 @@ ConvexBase* ConvexBase::convexHull(const Vec3f* pts, unsigned int num_points,
                                    const char* qhullCommand) {
 #ifdef HPP_FCL_HAS_QHULL
   if (num_points <= 3) {
-    throw std::invalid_argument(
+    HPP_FCL_THROW_PRETTY(
         "You shouldn't use this function with less than"
-        " 4 points.");
+        " 4 points.",
+        std::invalid_argument);
   }
   assert(pts[0].data() + 3 == pts[1].data());
 
@@ -70,7 +71,7 @@ ConvexBase* ConvexBase::convexHull(const Vec3f* pts, unsigned int num_points,
 
   if (qh.qhullStatus() != qh_ERRnone) {
     if (qh.hasQhullMessage()) std::cerr << qh.qhullMessage() << std::endl;
-    throw std::logic_error("Qhull failed");
+    HPP_FCL_THROW_PRETTY("Qhull failed", std::logic_error);
   }
 
   typedef std::size_t index_type;
@@ -143,9 +144,10 @@ ConvexBase* ConvexBase::convexHull(const Vec3f* pts, unsigned int num_points,
       }
     } else {
       if (keepTriangles) {  // TODO I think there is a memory leak here.
-        throw std::invalid_argument(
+        HPP_FCL_THROW_PRETTY(
             "You requested to keep triangles so you "
-            "must pass option \"Qt\" to qhull via the qhull command argument.");
+            "must pass option \"Qt\" to qhull via the qhull command argument.",
+            std::invalid_argument);
       }
       // Non-simplicial faces have more than 3 vertices and contains a list of
       // rigdes. Ridges are (3-1)D simplex (i.e. one edge). We mark the two
@@ -182,7 +184,7 @@ ConvexBase* ConvexBase::convexHull(const Vec3f* pts, unsigned int num_points,
   for (size_t i = 0; i < static_cast<size_t>(nvertex); ++i) {
     Neighbors& n = neighbors_[i];
     if (nneighbors[i].size() >= (std::numeric_limits<unsigned char>::max)())
-      throw std::logic_error("Too many neighbors.");
+      HPP_FCL_THROW_PRETTY("Too many neighbors.", std::logic_error);
     n.count_ = (unsigned char)nneighbors[i].size();
     n.n_ = p_nneighbors;
     p_nneighbors =
@@ -191,8 +193,9 @@ ConvexBase* ConvexBase::convexHull(const Vec3f* pts, unsigned int num_points,
   assert(p_nneighbors == convex->nneighbors_->data() + c_nneighbors);
   return convex;
 #else
-  throw std::logic_error(
-      "Library built without qhull. Cannot build object of this type.");
+  HPP_FCL_THROW_PRETTY(
+      "Library built without qhull. Cannot build object of this type.",
+      std::logic_error);
   HPP_FCL_UNUSED_VARIABLE(pts);
   HPP_FCL_UNUSED_VARIABLE(num_points);
   HPP_FCL_UNUSED_VARIABLE(keepTriangles);
@@ -203,9 +206,10 @@ ConvexBase* ConvexBase::convexHull(const Vec3f* pts, unsigned int num_points,
 #ifdef HPP_FCL_HAS_QHULL
 void ConvexBase::buildDoubleDescription() {
   if (num_points <= 3) {
-    throw std::invalid_argument(
+    HPP_FCL_THROW_PRETTY(
         "You shouldn't use this function with a convex less than"
-        " 4 points.");
+        " 4 points.",
+        std::invalid_argument);
   }
 
   Qhull qh;
@@ -215,7 +219,7 @@ void ConvexBase::buildDoubleDescription() {
 
   if (qh.qhullStatus() != qh_ERRnone) {
     if (qh.hasQhullMessage()) std::cerr << qh.qhullMessage() << std::endl;
-    throw std::logic_error("Qhull failed");
+    HPP_FCL_THROW_PRETTY("Qhull failed", std::logic_error);
   }
 
   buildDoubleDescriptionFromQHullResult(qh);