Skip to content

Commit

Permalink
Ran pre-commit to update according to new style guide
Browse files Browse the repository at this point in the history
  • Loading branch information
Shobuj-Paul committed Sep 14, 2023
1 parent 7466b65 commit 0381cb4
Show file tree
Hide file tree
Showing 30 changed files with 56 additions and 56 deletions.
4 changes: 2 additions & 2 deletions moveit_core/collision_detection/src/collision_matrix.cpp
Expand Up @@ -64,10 +64,10 @@ AllowedCollisionMatrix::AllowedCollisionMatrix(const srdf::Model& srdf)
for (const std::string& name : srdf.getNoDefaultCollisionLinks())
setDefaultEntry(name, collision_detection::AllowedCollision::ALWAYS);
// re-enable specific collision pairs
for (auto const& collision : srdf.getEnabledCollisionPairs())
for (const auto& collision : srdf.getEnabledCollisionPairs())
setEntry(collision.link1_, collision.link2_, false);
// *finally* disable selected collision pairs
for (auto const& collision : srdf.getDisabledCollisionPairs())
for (const auto& collision : srdf.getDisabledCollisionPairs())
setEntry(collision.link1_, collision.link2_, true);
}

Expand Down
Expand Up @@ -43,7 +43,7 @@
#include <rclcpp/time.hpp>
#include <memory>

const static double EPSILON{ 0.0001 };
static const double EPSILON{ 0.0001 };

namespace collision_detection
{
Expand Down
Expand Up @@ -156,7 +156,7 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase

/** @brief Signature for a cost function used to evaluate IK solutions. */
using IKCostFn = std::function<double(const geometry_msgs::msg::Pose&, const moveit::core::RobotState&,
moveit::core::JointModelGroup const*, const std::vector<double>&)>;
const moveit::core::JointModelGroup*, const std::vector<double>&)>;

/**
* @brief Given a desired pose of the end-effector, compute the joint angles to reach it
Expand Down
Expand Up @@ -398,18 +398,18 @@ std::ostream& operator<<(std::ostream& out, const RobotTrajectory& trajectory);
/// active joint distances between the two states (L1 norm).
/// \param[in] trajectory Given robot trajectory
/// \return Length of the robot trajectory [rad]
[[nodiscard]] double path_length(RobotTrajectory const& trajectory);
[[nodiscard]] double path_length(const RobotTrajectory& trajectory);

/// \brief Calculate the smoothness of a given trajectory
/// \param[in] trajectory Given robot trajectory
/// \return Smoothness of the given trajectory
/// or nullopt if it is not possible to calculate the smoothness
[[nodiscard]] std::optional<double> smoothness(RobotTrajectory const& trajectory);
[[nodiscard]] std::optional<double> smoothness(const RobotTrajectory& trajectory);

/// \brief Calculate the waypoint density of a trajectory
/// \param[in] trajectory Given robot trajectory
/// \return Waypoint density of the given trajectory
/// or nullopt if it is not possible to calculate the density
[[nodiscard]] std::optional<double> waypoint_density(RobotTrajectory const& trajectory);
[[nodiscard]] std::optional<double> waypoint_density(const RobotTrajectory& trajectory);

} // namespace robot_trajectory
12 changes: 6 additions & 6 deletions moveit_core/robot_trajectory/src/robot_trajectory.cpp
Expand Up @@ -636,19 +636,19 @@ std::ostream& operator<<(std::ostream& out, const RobotTrajectory& trajectory)
return out;
}

double path_length(RobotTrajectory const& trajectory)
double path_length(const RobotTrajectory& trajectory)
{
auto trajectory_length = 0.0;
for (std::size_t index = 1; index < trajectory.getWayPointCount(); ++index)
{
auto const& first = trajectory.getWayPoint(index - 1);
auto const& second = trajectory.getWayPoint(index);
const auto& first = trajectory.getWayPoint(index - 1);
const auto& second = trajectory.getWayPoint(index);
trajectory_length += first.distance(second);
}
return trajectory_length;
}

std::optional<double> smoothness(RobotTrajectory const& trajectory)
std::optional<double> smoothness(const RobotTrajectory& trajectory)
{
if (trajectory.getWayPointCount() > 2)
{
Expand Down Expand Up @@ -686,13 +686,13 @@ std::optional<double> smoothness(RobotTrajectory const& trajectory)
return std::nullopt;
}

std::optional<double> waypoint_density(RobotTrajectory const& trajectory)
std::optional<double> waypoint_density(const RobotTrajectory& trajectory)
{
// Only calculate density if more than one waypoint exists
if (trajectory.getWayPointCount() > 1)
{
// Calculate path length
auto const length = path_length(trajectory);
const auto length = path_length(trajectory);
if (length > 0.0)
{
auto density = static_cast<double>(trajectory.getWayPointCount()) / length;
Expand Down
Expand Up @@ -108,7 +108,7 @@ class RuckigSmoothing
*/
[[nodiscard]] static bool getRobotModelBounds(const double max_velocity_scaling_factor,
const double max_acceleration_scaling_factor,
moveit::core::JointModelGroup const* const group,
const moveit::core::JointModelGroup* const group,
ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);

/**
Expand Down
10 changes: 5 additions & 5 deletions moveit_core/trajectory_processing/src/ruckig_traj_smoothing.cpp
Expand Up @@ -75,7 +75,7 @@ bool RuckigSmoothing::applySmoothing(robot_trajectory::RobotTrajectory& trajecto
}

// Kinematic limits (vels/accels/jerks) from RobotModel
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
const size_t num_dof = group->getVariableCount();
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input{ num_dof };
if (!getRobotModelBounds(max_velocity_scaling_factor, max_acceleration_scaling_factor, group, ruckig_input))
Expand Down Expand Up @@ -109,7 +109,7 @@ bool RuckigSmoothing::applySmoothing(robot_trajectory::RobotTrajectory& trajecto
}

// Set default kinematic limits (vels/accels/jerks)
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
const size_t num_dof = group->getVariableCount();
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input{ num_dof };
if (!getRobotModelBounds(max_velocity_scaling_factor, max_acceleration_scaling_factor, group, ruckig_input))
Expand Down Expand Up @@ -176,7 +176,7 @@ bool RuckigSmoothing::applySmoothing(robot_trajectory::RobotTrajectory& trajecto

bool RuckigSmoothing::validateGroup(const robot_trajectory::RobotTrajectory& trajectory)
{
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
if (!group)
{
RCLCPP_ERROR(LOGGER, "The planner did not set the group the plan was computed for");
Expand All @@ -187,7 +187,7 @@ bool RuckigSmoothing::validateGroup(const robot_trajectory::RobotTrajectory& tra

bool RuckigSmoothing::getRobotModelBounds(const double max_velocity_scaling_factor,
const double max_acceleration_scaling_factor,
moveit::core::JointModelGroup const* const group,
const moveit::core::JointModelGroup* const group,
ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input)
{
const size_t num_dof = group->getVariableCount();
Expand Down Expand Up @@ -244,7 +244,7 @@ bool RuckigSmoothing::runRuckig(robot_trajectory::RobotTrajectory& trajectory,
const bool mitigate_overshoot, const double overshoot_threshold)
{
const size_t num_waypoints = trajectory.getWayPointCount();
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
const size_t num_dof = group->getVariableCount();
ruckig::OutputParameter<ruckig::DynamicDOFs> ruckig_output{ num_dof };

Expand Down
Expand Up @@ -158,9 +158,9 @@ TEST_F(RuckigTests, single_waypoint)
EXPECT_TRUE(
smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
// And the waypoint did not change
auto const new_first_waypoint = trajectory_->getFirstWayPointPtr();
auto const& variable_names = new_first_waypoint->getVariableNames();
for (std::string const& variable_name : variable_names)
const auto new_first_waypoint = trajectory_->getFirstWayPointPtr();
const auto& variable_names = new_first_waypoint->getVariableNames();
for (const std::string& variable_name : variable_names)
{
EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
new_first_waypoint->getVariablePosition(variable_name));
Expand Down
2 changes: 1 addition & 1 deletion moveit_kinematics/test/test_kinematics_plugin.cpp
Expand Up @@ -85,7 +85,7 @@ class SharedData
int num_nearest_ik_tests_;
bool publish_trajectory_;

SharedData(SharedData const&) = delete; // this is a singleton
SharedData(const SharedData&) = delete; // this is a singleton
SharedData()
{
initialize();
Expand Down
Expand Up @@ -57,7 +57,7 @@ class ConstrainedGoalSampler : public ompl::base::GoalLazySamples

private:
bool sampleUsingConstraintSampler(const ompl::base::GoalLazySamples* gls, ompl::base::State* new_goal);
bool stateValidityCallback(ompl::base::State* new_goal, moveit::core::RobotState const* state,
bool stateValidityCallback(ompl::base::State* new_goal, const moveit::core::RobotState* state,
const moveit::core::JointModelGroup* /*jmg*/, const double* /*jpos*/,
bool verbose = false) const;
bool checkStateValidity(ompl::base::State* new_goal, const moveit::core::RobotState& state,
Expand Down
Expand Up @@ -77,7 +77,7 @@ bool ompl_interface::ConstrainedGoalSampler::checkStateValidity(ob::State* new_g
}

bool ompl_interface::ConstrainedGoalSampler::stateValidityCallback(ob::State* new_goal,
moveit::core::RobotState const* state,
const moveit::core::RobotState* state,
const moveit::core::JointModelGroup* jmg,
const double* jpos, bool verbose) const
{
Expand Down
Expand Up @@ -68,10 +68,10 @@ class TestThreadSafeStateStorage : public ompl_interface_testing::LoadTestRobot,
auto robot_state_stored = tss.getStateStorage();

// Check if robot_state_stored's joint angles matches with what we set
for (auto const& joint_name : robot_state_->getVariableNames())
for (const auto& joint_name : robot_state_->getVariableNames())
{
auto const expected_value = robot_state_->getVariablePosition(joint_name);
auto const actual_value = robot_state_stored->getVariablePosition(joint_name);
const auto expected_value = robot_state_->getVariablePosition(joint_name);
const auto actual_value = robot_state_stored->getVariablePosition(joint_name);
EXPECT_EQ(actual_value, expected_value) << "Expecting joint value for " << joint_name << " to match.";
}
}
Expand Down
Expand Up @@ -154,7 +154,7 @@ void TrajectoryGenerator::checkJointGoalConstraint(const moveit_msgs::msg::Const
const std::vector<std::string>& expected_joint_names,
const std::string& group_name) const
{
for (auto const& joint_constraint : constraint.joint_constraints)
for (const auto& joint_constraint : constraint.joint_constraints)
{
const std::string& curr_joint_name{ joint_constraint.joint_name };
if (std::find(expected_joint_names.cbegin(), expected_joint_names.cend(), curr_joint_name) ==
Expand Down
Expand Up @@ -102,7 +102,7 @@ void TrajectoryGeneratorPTP::planPTP(const std::map<std::string, double>& start_

// check if goal already reached
bool goal_reached = true;
for (auto const& goal : goal_pos)
for (const auto& goal : goal_pos)
{
if (fabs(start_pos.at(goal.first) - goal.second) >= MIN_MOVEMENT)
{
Expand Down
Expand Up @@ -72,7 +72,7 @@ static constexpr double DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE{ 1e-8 };
/**
* @brief Convert degree to rad.
*/
inline static constexpr double deg2Rad(double angle)
static inline constexpr double deg2Rad(double angle)
{
return (angle / 180.0) * M_PI;
}
Expand All @@ -88,7 +88,7 @@ inline std::string getJointName(size_t joint_number, const std::string& joint_pr
*/
pilz_industrial_motion_planner::JointLimitsContainer createFakeLimits(const std::vector<std::string>& joint_names);

inline std::string demangle(char const* name)
inline std::string demangle(const char* name)
{
return boost::core::demangle(name);
}
Expand Down
Expand Up @@ -59,7 +59,7 @@ class SolverMock
class JointModelGroupMock
{
public:
MOCK_CONST_METHOD0(getSolverInstance, SolverMock const*());
MOCK_CONST_METHOD0(getSolverInstance, const SolverMock*());
MOCK_CONST_METHOD0(getName, const std::string&());
};

Expand Down
Expand Up @@ -173,7 +173,7 @@ class XmlTestdataLoader : public TestdataLoader
/**
* @brief Converts string vector to double vector.
*/
inline static std::vector<double> strVec2doubleVec(std::vector<std::string>& strVec);
static inline std::vector<double> strVec2doubleVec(std::vector<std::string>& strVec);

public:
/**
Expand Down
Expand Up @@ -50,7 +50,7 @@ namespace stomp_moveit
namespace filters
{
// \brief An empty placeholder filter that doesn't apply any updates to the trajectory.
const static FilterFn NO_FILTER = [](const Eigen::MatrixXd& /*values*/, Eigen::MatrixXd& /*filtered_values*/) {
static const FilterFn NO_FILTER = [](const Eigen::MatrixXd& /*values*/, Eigen::MatrixXd& /*filtered_values*/) {
return true;
};

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/stomp/src/stomp_moveit_planner_plugin.cpp
Expand Up @@ -87,7 +87,7 @@ class StompPlannerManager : public PlannerManager
return nullptr;
}

auto const params = param_listener_->get_params();
const auto params = param_listener_->get_params();

std::shared_ptr<StompPlanningContext> planning_context =
std::make_shared<StompPlanningContext>("STOMP", req.group_name, params);
Expand Down
12 changes: 6 additions & 6 deletions moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
Expand Up @@ -112,7 +112,7 @@ BenchmarkExecutor::~BenchmarkExecutor()
return false;
}

auto const& pipeline = moveit_cpp_->getPlanningPipelines().at(planning_pipeline_name);
const auto& pipeline = moveit_cpp_->getPlanningPipelines().at(planning_pipeline_name);
// Verify the pipeline has successfully initialized a planner
if (!pipeline->getPlannerManager())
{
Expand Down Expand Up @@ -861,7 +861,7 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request
std::chrono::system_clock::time_point start = std::chrono::system_clock::now();

// Planning pipeline benchmark
auto const response = planning_component->plan(plan_req_params, planning_scene_);
const auto response = planning_component->plan(plan_req_params, planning_scene_);

solved[j] = bool(response.error_code);

Expand Down Expand Up @@ -924,7 +924,7 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request

// Create multi-pipeline request
moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters multi_pipeline_plan_request;
for (auto const& pipeline_planner_id_pair : parallel_pipeline_entry.second)
for (const auto& pipeline_planner_id_pair : parallel_pipeline_entry.second)
{
moveit_cpp::PlanningComponent::PlanRequestParameters plan_req_params = {
.planner_id = pipeline_planner_id_pair.second,
Expand Down Expand Up @@ -959,11 +959,11 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request
// Solve problem
std::chrono::system_clock::time_point start = std::chrono::system_clock::now();

auto const t1 = std::chrono::system_clock::now();
auto const response = planning_component->plan(multi_pipeline_plan_request,
const auto t1 = std::chrono::system_clock::now();
const auto response = planning_component->plan(multi_pipeline_plan_request,
&moveit::planning_pipeline_interfaces::getShortestSolution,
nullptr, planning_scene_);
auto const t2 = std::chrono::system_clock::now();
const auto t2 = std::chrono::system_clock::now();

solved[j] = bool(response.error_code);

Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/benchmarks/src/BenchmarkOptions.cpp
Expand Up @@ -255,10 +255,10 @@ bool BenchmarkOptions::readPlannerConfigs(const rclcpp::Node::SharedPtr& node)

parallel_planning_pipelines[parallel_pipeline] = pipeline_planner_id_pairs;

for (auto const& entry : parallel_planning_pipelines)
for (const auto& entry : parallel_planning_pipelines)
{
RCLCPP_INFO(LOGGER, "Parallel planning pipeline '%s'", entry.first.c_str());
for (auto const& pair : entry.second)
for (const auto& pair : entry.second)
{
RCLCPP_INFO(LOGGER, " '%s': '%s'", pair.first.c_str(), pair.second.c_str());
}
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/benchmarks/src/RunBenchmark.cpp
Expand Up @@ -97,7 +97,7 @@ int main(int argc, char** argv)
return 1;
}
// Running benchmarks
for (auto const& name : scene_names)
for (const auto& name : scene_names)
{
options.scene_name = name;
if (!server.runBenchmarks(options))
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
Expand Up @@ -261,7 +261,7 @@ GLuint mesh_filter::GLRenderer::createShader(GLuint shaderType, const string& Sh
GLuint shader_id = glCreateShader(shaderType);

// Compile Shader
char const* source_pointer = ShaderCode.c_str();
const char* source_pointer = ShaderCode.c_str();
glShaderSource(shader_id, 1, &source_pointer, nullptr);
glCompileShader(shader_id);

Expand Down
Expand Up @@ -140,7 +140,7 @@ class KinematicsPluginLoader::KinematicsLoaderImpl

// just to be sure, do not call the same pluginlib instance allocation function in parallel
std::scoped_lock slock(lock_);
for (auto const& [group, solver] : possible_kinematics_solvers_)
for (const auto& [group, solver] : possible_kinematics_solvers_)
{
// Don't bother trying to load a solver for the wrong group
if (group != jmg->getName())
Expand Down Expand Up @@ -206,7 +206,7 @@ class KinematicsPluginLoader::KinematicsLoaderImpl

void status() const
{
for (auto const& [group, solver] : possible_kinematics_solvers_)
for (const auto& [group, solver] : possible_kinematics_solvers_)
{
RCLCPP_INFO(LOGGER, "Solver for group '%s': '%s' (search resolution = %lf)", group.c_str(), solver.c_str(),
search_res_.at(group));
Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/planning/moveit_cpp/src/planning_component.cpp
Expand Up @@ -189,7 +189,7 @@ planning_interface::MotionPlanResponse PlanningComponent::plan(
planning_scene->setCurrentState(request.start_state);
}

auto const motion_plan_response_vector = moveit::planning_pipeline_interfaces::planWithParallelPipelines(
const auto motion_plan_response_vector = moveit::planning_pipeline_interfaces::planWithParallelPipelines(
requests, planning_scene, moveit_cpp_->getPlanningPipelines(), stopping_criterion_callback,
solution_selection_function);

Expand Down Expand Up @@ -354,7 +354,7 @@ std::vector<::planning_interface::MotionPlanRequest> PlanningComponent::getMotio
{
std::vector<::planning_interface::MotionPlanRequest> motion_plan_requests;
motion_plan_requests.reserve(multi_pipeline_plan_request_parameters.plan_request_parameter_vector.size());
for (auto const& plan_request_parameters : multi_pipeline_plan_request_parameters.plan_request_parameter_vector)
for (const auto& plan_request_parameters : multi_pipeline_plan_request_parameters.plan_request_parameter_vector)
{
motion_plan_requests.push_back(getMotionPlanRequest(plan_request_parameters));
}
Expand Down
Expand Up @@ -76,7 +76,7 @@ const std::vector<::planning_interface::MotionPlanResponse> planWithParallelPipe

// Print a warning if more parallel planning problems than available concurrent threads are defined. If
// std::thread::hardware_concurrency() is not defined, the command returns 0 so the check does not work
auto const hardware_concurrency = std::thread::hardware_concurrency();
const auto hardware_concurrency = std::thread::hardware_concurrency();
if (motion_plan_requests.size() > hardware_concurrency && hardware_concurrency != 0)
{
RCLCPP_WARN(LOGGER,
Expand Down
Expand Up @@ -44,7 +44,7 @@ ::planning_interface::MotionPlanResponse
getShortestSolution(const std::vector<::planning_interface::MotionPlanResponse>& solutions)
{
// Find trajectory with minimal path
auto const shortest_trajectory = std::min_element(solutions.begin(), solutions.end(),
const auto shortest_trajectory = std::min_element(solutions.begin(), solutions.end(),
[](const ::planning_interface::MotionPlanResponse& solution_a,
const ::planning_interface::MotionPlanResponse& solution_b) {
// If both solutions were successful, check which path is shorter
Expand Down

0 comments on commit 0381cb4

Please sign in to comment.