summarylogtreecommitdiffstats
path: root/fix-console-bridge-functions.patch
blob: 69cab8e5314d35d0f73733ec7d6214ec5061c6cd (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
diff --git a/src/bodies.cpp b/src/bodies.cpp
index 700e4f2..97cff84 100644
--- a/src/bodies.cpp
+++ b/src/bodies.cpp
@@ -788,7 +788,7 @@ void bodies::ConvexMesh::useDimensions(const shapes::Shape *shape)
 
   if (exitcode != 0)
   {
-    logWarn("Convex hull creation failed");
+    CONSOLE_BRIDGE_logWarn("Convex hull creation failed");
     qh_freeqhull (!qh_ALL);
     int curlong, totlong;
     qh_memfreeshort (&curlong, &totlong);
@@ -1174,7 +1174,7 @@ void bodies::BodyVector::setPose(unsigned int i, const Eigen::Affine3d& pose)
 {
   if (i >= bodies_.size())
   {
-    logError("There is no body at index %u", i);
+    CONSOLE_BRIDGE_logError("There is no body at index %u", i);
     return;
   }
 
@@ -1185,7 +1185,7 @@ const bodies::Body* bodies::BodyVector::getBody(unsigned int i) const
 {
   if (i >= bodies_.size())
   {
-    logError("There is no body at index %u", i);
+    CONSOLE_BRIDGE_logError("There is no body at index %u", i);
     return NULL;
   }
   else
diff --git a/src/body_operations.cpp b/src/body_operations.cpp
index 9f6dd1a..e9f45fd 100644
--- a/src/body_operations.cpp
+++ b/src/body_operations.cpp
@@ -59,7 +59,7 @@ bodies::Body* bodies::createBodyFromShape(const shapes::Shape *shape)
       body = new bodies::ConvexMesh(shape);
       break;
     default:
-      logError("Creating body from shape: Unknown shape type %d", (int)shape->type);
+      CONSOLE_BRIDGE_logError("Creating body from shape: Unknown shape type %d", (int)shape->type);
       break;
     }
 
@@ -112,7 +112,7 @@ Body* constructBodyFromMsgHelper(const T &shape_msg, const geometry_msgs::Pose &
       Eigen::Quaterniond q(pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z);
       if (fabs(q.squaredNorm() - 1.0) > 1e-3)
       {
-        logError("Quaternion is not normalized. Assuming identity.");
+        CONSOLE_BRIDGE_logError("Quaternion is not normalized. Assuming identity.");
         q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0);
       }
       Eigen::Affine3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q.toRotationMatrix());
diff --git a/src/mesh_operations.cpp b/src/mesh_operations.cpp
index 54c534c..2e4c751 100644
--- a/src/mesh_operations.cpp
+++ b/src/mesh_operations.cpp
@@ -133,7 +133,7 @@ Mesh* createMeshFromVertices(const EigenSTL::vector_Vector3d &source)
     return NULL;
 
   if (source.size() % 3 != 0)
-    logError("The number of vertices to construct a mesh from is not divisible by 3. Probably constructed triangles will not make sense.");
+    CONSOLE_BRIDGE_logError("The number of vertices to construct a mesh from is not divisible by 3. Probably constructed triangles will not make sense.");
 
   std::set<detail::LocalVertexType, detail::ltLocalVertexValue> vertices;
   std::vector<unsigned int> triangles;
@@ -220,7 +220,7 @@ Mesh* createMeshFromBinary(const char *buffer, std::size_t size, const Eigen::Ve
 {
   if (!buffer || size < 1)
   {
-    logWarn("Cannot construct mesh from empty binary buffer");
+    CONSOLE_BRIDGE_logWarn("Cannot construct mesh from empty binary buffer");
     return NULL;
   }
 
@@ -285,21 +285,21 @@ Mesh* createMeshFromResource(const std::string& resource, const Eigen::Vector3d
   }
   catch (resource_retriever::Exception& e)
   {
-    logError("%s", e.what());
+    CONSOLE_BRIDGE_logError("%s", e.what());
     return NULL;
   }
 
   if (res.size == 0)
   {
-    logWarn("Retrieved empty mesh for resource '%s'", resource.c_str());
+    CONSOLE_BRIDGE_logWarn("Retrieved empty mesh for resource '%s'", resource.c_str());
     return NULL;
   }
 
   Mesh *m = createMeshFromBinary(reinterpret_cast<const char*>(res.data.get()), res.size, scale, resource);
   if (!m)
   {
-    logWarn("Assimp reports no scene in %s.", resource.c_str());
-    logWarn("This could be because of a resource filename that is too long for the Assimp library, a known bug. As a workaround shorten the filename/path.");
+    CONSOLE_BRIDGE_logWarn("Assimp reports no scene in %s.", resource.c_str());
+    CONSOLE_BRIDGE_logWarn("This could be because of a resource filename that is too long for the Assimp library, a known bug. As a workaround shorten the filename/path.");
   }
   return m;
 }
@@ -344,7 +344,7 @@ Mesh* createMeshFromAsset(const aiScene* scene, const Eigen::Vector3d &scale, co
 {
   if (!scene->HasMeshes())
   {
-    logWarn("Assimp reports scene in %s has no meshes", resource_name.c_str());
+    CONSOLE_BRIDGE_logWarn("Assimp reports scene in %s has no meshes", resource_name.c_str());
     return NULL;
   }
   EigenSTL::vector_Vector3d vertices;
@@ -352,12 +352,12 @@ Mesh* createMeshFromAsset(const aiScene* scene, const Eigen::Vector3d &scale, co
   extractMeshData(scene, scene->mRootNode, aiMatrix4x4(), scale, vertices, triangles);
   if (vertices.empty())
   {
-    logWarn("There are no vertices in the scene %s", resource_name.c_str());
+    CONSOLE_BRIDGE_logWarn("There are no vertices in the scene %s", resource_name.c_str());
     return NULL;
   }
   if (triangles.empty())
   {
-    logWarn("There are no triangles in the scene %s", resource_name.c_str());
+    CONSOLE_BRIDGE_logWarn("There are no triangles in the scene %s", resource_name.c_str());
     return NULL;
   }
 
@@ -378,7 +378,7 @@ Mesh* createMeshFromShape(const Shape *shape)
         if (shape->type == shapes::CONE)
           return shapes::createMeshFromShape(static_cast<const shapes::Cone&>(*shape));
         else
-          logError("Conversion of shape of type '%s' to a mesh is not known", shapeStringName(shape).c_str());
+          CONSOLE_BRIDGE_logError("Conversion of shape of type '%s' to a mesh is not known", shapeStringName(shape).c_str());
   return NULL;
 }
 
diff --git a/src/shape_operations.cpp b/src/shape_operations.cpp
index e3a32cd..7b63b15 100644
--- a/src/shape_operations.cpp
+++ b/src/shape_operations.cpp
@@ -62,7 +62,7 @@ Shape* constructShapeFromMsg(const shape_msgs::Mesh &shape_msg)
 {
   if (shape_msg.triangles.empty() || shape_msg.vertices.empty())
   {
-    logWarn("Mesh definition is empty");
+    CONSOLE_BRIDGE_logWarn("Mesh definition is empty");
     return NULL;
   }
   else
@@ -117,7 +117,7 @@ Shape* constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
                              shape_msg.dimensions[shape_msgs::SolidPrimitive::CONE_HEIGHT]);
         }
   if (shape == NULL)
-    logError("Unable to construct shape corresponding to shape_msg of type %d", (int)shape_msg.type);
+    CONSOLE_BRIDGE_logError("Unable to construct shape corresponding to shape_msg of type %d", (int)shape_msg.type);
 
   return shape;
 }
@@ -202,7 +202,7 @@ bool constructMarkerFromShape(const Shape* shape, visualization_msgs::Marker &ma
     }
     catch (std::runtime_error &ex)
     {
-      logError("%s", ex.what());
+      CONSOLE_BRIDGE_logError("%s", ex.what());
     }
     if (ok)
       return true;
@@ -451,7 +451,7 @@ bool constructMsgFromShape(const Shape* shape, ShapeMsg &shape_msg)
             }
             else
             {
-              logError("Unable to construct shape message for shape of type %d", (int)shape->type);
+              CONSOLE_BRIDGE_logError("Unable to construct shape message for shape of type %d", (int)shape->type);
               return false;
             }
 
@@ -512,7 +512,7 @@ void saveAsText(const Shape *shape, std::ostream &out)
             }
             else
             {
-              logError("Unable to save shape of type %d", (int)shape->type);
+              CONSOLE_BRIDGE_logError("Unable to save shape of type %d", (int)shape->type);
             }
 }
 
@@ -580,7 +580,7 @@ Shape* constructShapeFromText(std::istream &in)
                   m->computeVertexNormals();
                 }
                 else
-                  logError("Unknown shape type: '%s'", type.c_str());
+                  CONSOLE_BRIDGE_logError("Unknown shape type: '%s'", type.c_str());
     }
   }
   return result;
diff --git a/src/shapes.cpp b/src/shapes.cpp
index 292012d..48c6cc1 100644
--- a/src/shapes.cpp
+++ b/src/shapes.cpp
@@ -224,12 +224,12 @@ shapes::Shape* shapes::OcTree::clone() const
 
 void shapes::OcTree::scaleAndPadd(double scale, double padd)
 {
-  logWarn("OcTrees cannot be scaled or padded");
+  CONSOLE_BRIDGE_logWarn("OcTrees cannot be scaled or padded");
 }
 
 void shapes::Plane::scaleAndPadd(double scale, double padding)
 {
-  logWarn("Planes cannot be scaled or padded");
+  CONSOLE_BRIDGE_logWarn("Planes cannot be scaled or padded");
 }
 
 void shapes::Shape::scale(double scale)