Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix log function deprecation warnings. #72

Merged
merged 1 commit into from
Jan 15, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions src/bodies.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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;
}

Expand All @@ -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
Expand Down
20 changes: 10 additions & 10 deletions src/mesh_operations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
}

Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -344,20 +344,20 @@ 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;
std::vector<unsigned int> triangles;
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;
}

Expand All @@ -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;
}

Expand Down
12 changes: 6 additions & 6 deletions src/shape_operations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
}

Expand Down Expand Up @@ -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);
}
}

Expand Down Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions src/shapes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down