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

Apply clang tidy fix to entire code base (Part 1) #1366

Merged
merged 17 commits into from
Feb 28, 2019
Merged
Show file tree
Hide file tree
Changes from 15 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
---
Checks: '-*,
performance-*,
llvm-namespace-comment,
modernize-redundant-void-arg,
modernize-use-nullptr,
modernize-use-default,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -901,7 +901,7 @@ void cleanCollisionGeometryCache()
cache2.bumpUseCount(true);
}
}
}
} // namespace collision_detection

void collision_detection::CollisionData::enableGroup(const robot_model::RobotModelConstPtr& robot_model)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <boost/thread/mutex.hpp>
#include <tf2_eigen/tf2_eigen.h>
#include <memory>
#include <utility>

namespace collision_detection
{
Expand Down Expand Up @@ -150,7 +151,7 @@ void getBodySphereVisualizationMarkers(GroupStateRepresentationConstPtr& gsr, st

// creating sphere marker
visualization_msgs::Marker sphere_marker;
sphere_marker.header.frame_id = reference_frame;
sphere_marker.header.frame_id = std::move(reference_frame);
sphere_marker.header.stamp = ros::Time(0);
sphere_marker.ns = robot_ns;
sphere_marker.id = 0;
Expand Down Expand Up @@ -220,4 +221,4 @@ void getBodySphereVisualizationMarkers(GroupStateRepresentationConstPtr& gsr, st
}
}
}
}
} // namespace collision_detection
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ bool collision_detection::getCollisionSphereCollision(const distance_field::Dist
}
}

return colls.size() > 0;
return !colls.empty();
}

///
Expand Down Expand Up @@ -402,11 +402,7 @@ bool collision_detection::doBoundingSpheresIntersect(const PosedBodySphereDecomp
double p2_radius = p2->getBoundingSphereRadius();

double dist = (p1_sphere_center - p2_sphere_center).squaredNorm();
if (dist < (p1_radius + p2_radius))
{
return true;
}
return false;
return dist < (p1_radius + p2_radius);
}

void collision_detection::getCollisionSphereMarkers(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -757,7 +757,7 @@ DistanceFieldCacheEntryPtr CollisionRobotDistanceField::generateDistanceFieldCac
continue;
}

if (link_state->getShapes().size() > 0)
if (!link_state->getShapes().empty())
{
dfce->link_has_geometry_.push_back(true);
dfce->link_body_indices_.push_back(link_body_decomposition_index_map_.find(link_name)->second);
Expand Down Expand Up @@ -874,7 +874,7 @@ DistanceFieldCacheEntryPtr CollisionRobotDistanceField::generateDistanceFieldCac
}
}

const std::vector<std::string> state_variable_names = state.getVariableNames();
const std::vector<std::string>& state_variable_names = state.getVariableNames();
for (std::vector<std::string>::const_iterator name_iter = state_variable_names.begin();
name_iter != state_variable_names.end(); name_iter++)
{
Expand Down Expand Up @@ -1372,4 +1372,4 @@ bool CollisionRobotDistanceField::compareCacheEntryToAllowedCollisionMatrix(
// if(dfce->acm.find
// }
// }
}
} // namespace collision_detection
Original file line number Diff line number Diff line change
Expand Up @@ -93,4 +93,4 @@ void CollisionRobotHybrid::checkSelfCollisionDistanceField(const collision_detec
{
crobot_distance_->checkSelfCollision(req, res, state, acm, gsr);
}
}
} // namespace collision_detection
Original file line number Diff line number Diff line change
Expand Up @@ -562,7 +562,7 @@ CollisionWorldDistanceField::DistanceFieldCacheEntryPtr CollisionWorldDistanceFi
dfce->distance_field_->addPointsToField(add_points);
return dfce;
}
}
} // namespace collision_detection

#include <moveit/collision_distance_field/collision_detector_allocator_distance_field.h>
const std::string collision_detection::CollisionDetectorAllocatorDistanceField::NAME_("DISTANCE_FIELD");
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ void CollisionWorldHybrid::getAllCollisions(const CollisionRequest& req, Collisi
{
cworld_distance_->getAllCollisions(req, res, robot, state, acm, gsr);
}
}
} // namespace collision_detection

#include <moveit/collision_distance_field/collision_detector_allocator_hybrid.h>
const std::string collision_detection::CollisionDetectorAllocatorHybrid::NAME_("HYBRID");
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class DistanceFieldCollisionDetectionTester : public testing::Test
}
xml_file.close();
urdf_model_ = urdf::parseURDF(xml_string);
urdf_ok_ = urdf_model_ ? true : false;
urdf_ok_ = static_cast<bool>(urdf_model_);
}
else
urdf_ok_ = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -520,7 +520,7 @@ void samplingIkCallbackFnAdapter(robot_state::RobotState* state, const robot_mod
else
error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
}
}
} // namespace

bool IKConstraintSampler::sample(robot_state::RobotState& state, const robot_state::RobotState& reference_state,
unsigned int max_attempts)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -428,4 +428,4 @@ const std::vector<std::string>& PR2ArmKinematicsPlugin::getLinkNames() const
return fk_solver_info_.link_names;
}

} // namespace
} // namespace pr2_arm_kinematics
Original file line number Diff line number Diff line change
Expand Up @@ -770,4 +770,4 @@ bool PropagationDistanceField::readFromStream(std::istream& is)
addNewObstacleVoxels(obs_points);
return true;
}
}
} // namespace distance_field
2 changes: 1 addition & 1 deletion moveit_core/dynamics_solver/src/dynamics_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ inline geometry_msgs::Vector3 transformVector(const Eigen::Isometry3d& transform

return result;
}
}
} // namespace

DynamicsSolver::DynamicsSolver(const robot_model::RobotModelConstPtr& robot_model, const std::string& group_name,
const geometry_msgs::Vector3& gravity_vector)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/kinematic_constraints/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -527,4 +527,4 @@ bool constructConstraints(XmlRpc::XmlRpcValue& params, moveit_msgs::Constraints&
constraints.name = static_cast<std::string>(params["name"]);
return collectConstraints(params["constraints"], constraints);
}
}
} // namespace kinematic_constraints
6 changes: 2 additions & 4 deletions moveit_core/kinematics_base/src/kinematics_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace kinematics
const double KinematicsBase::DEFAULT_SEARCH_DISCRETIZATION = 0.1;
const double KinematicsBase::DEFAULT_TIMEOUT = 1.0;

static void noDeleter(const moveit::core::RobotModel*)
static void noDeleter(const moveit::core::RobotModel* /*unused*/)
{
}

Expand Down Expand Up @@ -186,9 +186,7 @@ KinematicsBase::KinematicsBase()
supported_methods_.push_back(DiscretizationMethods::NO_DISCRETIZATION);
}

KinematicsBase::~KinematicsBase()
{
}
KinematicsBase::~KinematicsBase() = default;

bool KinematicsBase::getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_interface/src/planning_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ static ActiveContexts& getActiveContexts()
static ActiveContexts ac;
return ac;
}
}
} // namespace

PlanningContext::PlanningContext(const std::string& name, const std::string& group) : name_(name), group_(group)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ bool callPlannerInterfaceSolve(const planning_interface::PlannerManager* planner
else
return false;
}
}
} // namespace

bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
Expand Down Expand Up @@ -115,7 +115,7 @@ bool callAdapter2(const PlanningRequestAdapter* adapter, const PlanningRequestAd
return planner(planning_scene, req, res);
}
}
}
} // namespace

bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -812,7 +812,7 @@ class ShapeVisitorAddToCollisionObject : public boost::static_visitor<void>
moveit_msgs::CollisionObject* obj_;
const geometry_msgs::Pose* pose_;
};
}
} // namespace

bool PlanningScene::getCollisionObjectMsg(moveit_msgs::CollisionObject& collision_obj, const std::string& ns) const
{
Expand Down Expand Up @@ -1603,7 +1603,7 @@ bool PlanningScene::processAttachedCollisionObjectMsg(const moveit_msgs::Attache
poses.insert(poses.end(), ab->getFixedTransforms().begin(), ab->getFixedTransforms().end());
trajectory_msgs::JointTrajectory detach_posture =
object.detach_posture.joint_names.empty() ? ab->getDetachPosture() : object.detach_posture;
std::set<std::string> ab_touch_links = ab->getTouchLinks();
const std::set<std::string>& ab_touch_links = ab->getTouchLinks();
robot_state_->clearAttachedBody(object.object.id);
if (object.touch_links.empty())
robot_state_->attachBody(object.object.id, shapes, poses, ab_touch_links, object.link_name, detach_posture);
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/profiler/src/profiler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ struct SortDoubleByValue
return a.value_ > b.value_;
}
};
}
} // namespace
/// @endcond

void Profiler::printThreadInfo(std::ostream& out, const PerThread& data)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/joint_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ inline void printBoundHelper(std::ostream& out, double v)
else
out << v;
}
}
} // namespace

std::ostream& operator<<(std::ostream& out, const VariableBounds& b)
{
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/joint_model_group.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ bool jointPrecedes(const JointModel* a, const JointModel* b)

return false;
}
}
} // namespace

JointModelGroup::JointModelGroup(const std::string& group_name, const srdf::Model::Group& config,
const std::vector<const JointModel*>& unsorted_group_joints,
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/robot_model/src/robot_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ void computeCommonRootsHelper(const JointModel* joint, std::vector<int>& common_
computeCommonRootsHelper(ch[i], common_roots, size);
}
}
}
} // namespace

void RobotModel::computeCommonRoots()
{
Expand Down Expand Up @@ -840,7 +840,7 @@ static inline VariableBounds jointBoundsFromURDF(const urdf::Joint* urdf_joint)
}
return b;
}
}
} // namespace

JointModel* RobotModel::constructJointModel(const urdf::Joint* urdf_joint, const urdf::Link* child_link,
const srdf::Model& srdf_model)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_state/src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -357,7 +357,7 @@ static bool _robotStateMsgToRobotStateHelper(const Transforms* tf, const moveit_

return valid;
}
}
} // namespace

// ********************************************

Expand Down
4 changes: 2 additions & 2 deletions moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1381,7 +1381,7 @@ bool ikCallbackFnAdapter(RobotState* state, const JointModelGroup* group,
error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
return true;
}
}
} // namespace

bool RobotState::setToIKSolverFrame(Eigen::Isometry3d& pose, const kinematics::KinematicsBaseConstPtr& solver)
{
Expand Down Expand Up @@ -2343,7 +2343,7 @@ void getPoseString(std::ostream& ss, const Eigen::Isometry3d& pose, const std::s
ss << std::endl;
}
}
}
} // namespace

void RobotState::getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0,
bool last) const
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/robot_state/test/test_aabb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,13 @@ class TestAABB : public testing::Test
protected:
void SetUp() override{};

robot_state::RobotState loadModel(const std::string robot_name)
robot_state::RobotState loadModel(const std::string& robot_name)
{
robot_model::RobotModelPtr model = moveit::core::loadTestingRobotModel(robot_name);
return loadModel(model);
}

robot_state::RobotState loadModel(robot_model::RobotModelPtr model)
robot_state::RobotState loadModel(const robot_model::RobotModelPtr& model)
{
robot_state::RobotState robot_state = robot_state::RobotState(model);
robot_state.setToDefaultValues();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -602,4 +602,4 @@ void globalAdjustment(std::vector<SingleJointTrajectory>& t2, int num_joints, co
fit_cubic_spline(num_points, &time_diff[0], &t2[j].positions_[0], &t2[j].velocities_[0], &t2[j].accelerations_[0]);
}
}
}
} // namespace trajectory_processing
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ void printStats(const trajectory_msgs::JointTrajectory& trajectory, const std::v
for (std::size_t i = 0; i < trajectory.points.size(); ++i)
printPoint(trajectory.points[i], i);
}
}
} // namespace

// Applies velocity
void IterativeParabolicTimeParameterization::applyVelocityConstraints(robot_trajectory::RobotTrajectory& rob_trajectory,
Expand Down Expand Up @@ -294,7 +294,7 @@ void updateTrajectory(robot_trajectory::RobotTrajectory& rob_trajectory, const s
}
}
}
}
} // namespace

// Applies Acceleration constraints
void IterativeParabolicTimeParameterization::applyAccelerationConstraints(
Expand Down Expand Up @@ -484,4 +484,4 @@ bool IterativeParabolicTimeParameterization::computeTimeStamps(robot_trajectory:
updateTrajectory(trajectory, time_diff);
return true;
}
}
} // namespace trajectory_processing
2 changes: 1 addition & 1 deletion moveit_core/trajectory_processing/src/trajectory_tools.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,4 +47,4 @@ std::size_t trajectoryWaypointCount(const moveit_msgs::RobotTrajectory& trajecto
{
return std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
}
}
} // namespace trajectory_processing
Original file line number Diff line number Diff line change
Expand Up @@ -179,10 +179,10 @@ class RobotModelBuilder

private:
/** \brief Adds different collision geometries to a link. */
void addLinkCollision(const std::string& link_name, urdf::CollisionSharedPtr coll, geometry_msgs::Pose origin);
void addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& coll, geometry_msgs::Pose origin);

/** \brief Adds different visual geometries to a link. */
void addLinkVisual(const std::string& link_name, urdf::VisualSharedPtr vis, geometry_msgs::Pose origin);
void addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis, geometry_msgs::Pose origin);

/// The URDF model, holds all of the URDF components of the robot added so far.
urdf::ModelInterfaceSharedPtr urdf_model_;
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/utils/src/lexical_casts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,5 +87,5 @@ float toFloat(const std::string& s)
{
return toRealImpl<float>(s);
}
}
}
} // namespace core
} // namespace moveit
4 changes: 2 additions & 2 deletions moveit_core/utils/src/robot_model_test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ void RobotModelBuilder::addCollisionMesh(const std::string& link_name, const std
addLinkCollision(link_name, coll, origin);
}

void RobotModelBuilder::addLinkCollision(const std::string& link_name, urdf::CollisionSharedPtr collision,
void RobotModelBuilder::addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& collision,
geometry_msgs::Pose origin)
{
if (not urdf_model_->getLink(link_name))
Expand All @@ -255,7 +255,7 @@ void RobotModelBuilder::addLinkCollision(const std::string& link_name, urdf::Col
link->collision_array.push_back(collision);
}

void RobotModelBuilder::addLinkVisual(const std::string& link_name, urdf::VisualSharedPtr vis,
void RobotModelBuilder::addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis,
geometry_msgs::Pose origin)
{
if (not urdf_model_->getLink(link_name))
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/utils/src/xmlrpc_casts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,5 +87,5 @@ bool isStruct(XmlRpc::XmlRpcValue& v, const std::vector<std::string>& keys, cons

return missing.empty();
}
}
}
} // namespace core
} // namespace moveit