Skip to content

Commit

Permalink
Merge pull request #6011 from jwnimmer-tri/build-unused-parameter-col…
Browse files Browse the repository at this point in the history
…lision_shapes

Fix Wunused-parameter in multibody/collision and multibody/shapes
  • Loading branch information
soonho-tri authored May 5, 2017
2 parents 19d6ac4 + 136eec5 commit 6bb9e2b
Show file tree
Hide file tree
Showing 8 changed files with 40 additions and 44 deletions.
2 changes: 2 additions & 0 deletions drake/multibody/collision/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ drake_cc_library(
defines = ["BULLET_COLLISION"],
deps = [
":collision_api",
"//drake/common:unused",
"@bullet//:lib",
],
)
Expand Down Expand Up @@ -75,6 +76,7 @@ drake_cc_library(
],
deps = [
":collision_api",
"//drake/common:unused",
"@fcl//:lib",
],
)
Expand Down
6 changes: 6 additions & 0 deletions drake/multibody/collision/bullet_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/text_logging.h"
#include "drake/common/unused.h"
#include "drake/multibody/collision/drake_collision.h"

using Eigen::Isometry3d;
Expand Down Expand Up @@ -58,6 +59,8 @@ struct BinaryContactResultCallback
int partId0, int index0,
const btCollisionObjectWrapper* colObj1Wrap,
int partId1, int index1) {
drake::unused(cp, colObj0Wrap, partId0, index0, colObj1Wrap, partId1,
index1);
in_collision = true;
return 0;
}
Expand Down Expand Up @@ -131,20 +134,23 @@ std::unique_ptr<btCollisionShape> BulletModel::newBulletBoxShape(

std::unique_ptr<btCollisionShape> BulletModel::newBulletSphereShape(
const DrakeShapes::Sphere& geometry, bool use_margins) {
drake::unused(use_margins); // TODO(jwnimmer-tri) This seems bad.
std::unique_ptr<btCollisionShape> bt_shape(
new btSphereShape(geometry.radius));
return bt_shape;
}

std::unique_ptr<btCollisionShape> BulletModel::newBulletCylinderShape(
const DrakeShapes::Cylinder& geometry, bool use_margins) {
drake::unused(use_margins); // TODO(jwnimmer-tri) This seems bad.
std::unique_ptr<btCollisionShape> bt_shape(new btCylinderShapeZ(
btVector3(geometry.radius, geometry.radius, geometry.length / 2)));
return bt_shape;
}

std::unique_ptr<btCollisionShape> BulletModel::newBulletCapsuleShape(
const DrakeShapes::Capsule& geometry, bool use_margins) {
drake::unused(use_margins); // TODO(jwnimmer-tri) This seems bad.
std::unique_ptr<btCollisionShape> bt_shape(new btConvexHullShape());
dynamic_cast<btConvexHullShape*>(bt_shape.get())
->addPoint(btVector3(0, 0, -geometry.length / 2));
Expand Down
11 changes: 11 additions & 0 deletions drake/multibody/collision/fcl_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,14 @@
#include <fcl/fcl.h>

#include "drake/common/drake_assert.h"
#include "drake/common/unused.h"

namespace DrakeCollision {

// TODO(jamiesnape): Implement the model.

void FCLModel::DoAddElement(const Element& element) {
drake::unused(element);
DRAKE_ABORT_MSG("Not implemented.");
}

Expand All @@ -19,56 +21,65 @@ void FCLModel::updateModel() {
bool FCLModel::closestPointsAllToAll(const std::vector<ElementId>& ids_to_check,
bool use_margins,
std::vector<PointPair>& closest_points) {
drake::unused(ids_to_check, use_margins, closest_points);
DRAKE_ABORT_MSG("Not implemented.");
return false;
}

bool FCLModel::ComputeMaximumDepthCollisionPoints(
bool use_margins, std::vector<PointPair>& points) {
drake::unused(use_margins, points);
DRAKE_ABORT_MSG("Not implemented.");
return false;
}

bool FCLModel::closestPointsPairwise(const std::vector<ElementIdPair>& id_pairs,
bool use_margins,
std::vector<PointPair>& closest_points) {
drake::unused(id_pairs, use_margins, closest_points);
DRAKE_ABORT_MSG("Not implemented.");
return false;
}

void FCLModel::collisionDetectFromPoints(
const Eigen::Matrix3Xd& points, bool use_margins,
std::vector<PointPair>& closest_points) {
drake::unused(points, use_margins, closest_points);
DRAKE_ABORT_MSG("Not implemented.");
}

void FCLModel::ClearCachedResults(bool use_margins) {
drake::unused(use_margins);
DRAKE_ABORT_MSG("Not implemented.");
}

bool FCLModel::collisionRaycast(const Eigen::Matrix3Xd& origins,
const Eigen::Matrix3Xd& ray_endpoints,
bool use_margins, Eigen::VectorXd& distances,
Eigen::Matrix3Xd& normals) {
drake::unused(origins, ray_endpoints, use_margins, distances, normals);
DRAKE_ABORT_MSG("Not implemented.");
return false;
}

std::vector<PointPair> FCLModel::potentialCollisionPoints(bool use_margins) {
drake::unused(use_margins);
DRAKE_ABORT_MSG("Not implemented.");
return std::vector<PointPair>();
}

bool FCLModel::collidingPointsCheckOnly(
const std::vector<Eigen::Vector3d>& input_points,
double collision_threshold) {
drake::unused(input_points, collision_threshold);
DRAKE_ABORT_MSG("Not implemented.");
return false;
}

std::vector<size_t> FCLModel::collidingPoints(
const std::vector<Eigen::Vector3d>& input_points,
double collision_threshold) {
drake::unused(input_points, collision_threshold);
DRAKE_ABORT_MSG("Not implemented.");
return std::vector<size_t>();
}
Expand Down
23 changes: 1 addition & 22 deletions drake/multibody/collision/model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -80,28 +80,7 @@ bool Model::transformCollisionFrame(
}
}

bool closestPointsAllToAll(
const vector<ElementId>& ids_to_check,
bool use_margins,
// TODO(#2274) Fix NOLINTNEXTLINE(runtime/references).
vector<PointPair>& closest_points) {
return false;
}

bool collisionPointsAllToAll(
bool use_margins,
// TODO(#2274) Fix NOLINTNEXTLINE(runtime/references).
vector<PointPair>& points) {
return false;
}

bool closestPointsPairwise(
const vector<ElementIdPair>& id_pairs,
bool use_margins,
// TODO(#2274) Fix NOLINTNEXTLINE(runtime/references).
vector<PointPair>& closest_points) {
return false;
}
void Model::DoAddElement(const Element&) {}

/**
* A toString for the collision model.
Expand Down
2 changes: 1 addition & 1 deletion drake/multibody/collision/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,7 @@ class Model {
@param element The element that has been added.
@throws std::runtime_error If there was a problem processing the element. **/
virtual void DoAddElement(const Element& element) {}
virtual void DoAddElement(const Element& element);

// Protected member variables are forbidden by the style guide.
// Please do not add new references to this member. Instead, use
Expand Down
34 changes: 14 additions & 20 deletions drake/multibody/collision/unusable_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,77 +11,71 @@ void UnusableModel::updateModel() {
}

bool UnusableModel::updateElementWorldTransform(
ElementId, const Eigen::Isometry3d& T_local_to_world) {
ElementId, const Eigen::Isometry3d&) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return false;
}

bool UnusableModel::closestPointsAllToAll(
const std::vector<ElementId>& ids_to_check, bool use_margins,
std::vector<PointPair>& closest_points) {
const std::vector<ElementId>&, bool, std::vector<PointPair>&) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return false;
}

bool UnusableModel::ComputeMaximumDepthCollisionPoints(
bool use_margins, std::vector<PointPair>& points) {
bool, std::vector<PointPair>&) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return false;
}

bool UnusableModel::closestPointsPairwise(
const std::vector<ElementIdPair>& id_pairs, bool use_margins,
std::vector<PointPair>& closest_points) {
const std::vector<ElementIdPair>&, bool, std::vector<PointPair>&) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return false;
}

void UnusableModel::collisionDetectFromPoints(
const Eigen::Matrix3Xd& points, bool use_margins,
std::vector<PointPair>& closest_points) {
const Eigen::Matrix3Xd&, bool, std::vector<PointPair>&) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return;
}

void UnusableModel::ClearCachedResults(bool use_margins) {
void UnusableModel::ClearCachedResults(bool) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return;
}

bool UnusableModel::collisionRaycast(const Eigen::Matrix3Xd& origins,
const Eigen::Matrix3Xd& ray_endpoints,
bool use_margins,
Eigen::VectorXd& distances,
Eigen::Matrix3Xd& normals) {
bool UnusableModel::collisionRaycast(const Eigen::Matrix3Xd&,
const Eigen::Matrix3Xd&,
bool,
Eigen::VectorXd&,
Eigen::Matrix3Xd&) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return false;
}

std::vector<PointPair> UnusableModel::potentialCollisionPoints(
bool use_margins) {
std::vector<PointPair> UnusableModel::potentialCollisionPoints(bool) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return std::vector<PointPair>();
}

bool UnusableModel::collidingPointsCheckOnly(
const std::vector<Eigen::Vector3d>& input_points,
double collision_threshold) {
const std::vector<Eigen::Vector3d>&, double) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return false;
}

std::vector<size_t> UnusableModel::collidingPoints(
const std::vector<Eigen::Vector3d>& input_points,
double collision_threshold) {
const std::vector<Eigen::Vector3d>&, double) {
DRAKE_ABORT_MSG(
"Compile Drake with a collision library backend for collision support!");
return std::vector<size_t>();
Expand Down
1 change: 1 addition & 0 deletions drake/multibody/shapes/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ drake_cc_library(
],
deps = [
"//drake/common",
"//drake/common:unused",
"//drake/thirdParty:spruce",
"@tinyobjloader//:tinyobjloader",
],
Expand Down
5 changes: 4 additions & 1 deletion drake/multibody/shapes/geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

#include <Eigen/Dense>

#include "drake/common/unused.h"

namespace DrakeShapes {
enum Shape {
UNKNOWN = 0,
Expand Down Expand Up @@ -51,11 +53,12 @@ class Geometry {
* Returns the faces making up this geometry as a vector of triangles.
* Each triangle contains three indices into the vertex list returned
* by the Geometry getPoints() method.
* @param[out] faces Returns a vector of triangles describing
* @param[out] faces Returns a vector of triangles describing
* this geometry.
*/
// TODO(#2274) Fix NOLINTNEXTLINE(runtime/references).
virtual void getFaces(TrianglesVector* faces) const {
drake::unused(faces);
throw std::runtime_error("Error: getFaces() not implemented"
" for this geometry type.\n");
}
Expand Down

0 comments on commit 6bb9e2b

Please sign in to comment.