Skip to content

Commit

Permalink
Cleanup const-ref arguments to double+int (moveit#3560)
Browse files Browse the repository at this point in the history
* Add missing word in error message
* Replace const [double|int] reference arguments with plain const args
   There is no value in passing a const reference over passing the value directly.
   The latter saves an extra indirection.
  • Loading branch information
rhaschke committed Feb 6, 2024
1 parent 5dbdae1 commit 50eb4e7
Show file tree
Hide file tree
Showing 20 changed files with 50 additions and 49 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,7 @@ class RobotTrajectory
* @param after The waypoint index after (or equal to) the supplied duration.
* @param blend The progress (0 to 1) between the two waypoints, based on time (not based on joint distances).
*/
void findWayPointIndicesForDurationAfterStart(const double& duration, int& before, int& after, double& blend) const;
void findWayPointIndicesForDurationAfterStart(const double duration, int& before, int& after, double& blend) const;

// TODO support visitor function for interpolation, or at least different types.
/** @brief Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_trajectory/src/robot_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -439,7 +439,7 @@ RobotTrajectory& RobotTrajectory::setRobotTrajectoryMsg(const moveit::core::Robo
return setRobotTrajectoryMsg(st, trajectory);
}

void RobotTrajectory::findWayPointIndicesForDurationAfterStart(const double& duration, int& before, int& after,
void RobotTrajectory::findWayPointIndicesForDurationAfterStart(const double duration, int& before, int& after,
double& blend) const
{
if (duration < 0.0)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,15 +130,15 @@ class JointLimitsContainer
* @param joint_position
* @return
*/
bool verifyVelocityLimit(const std::string& joint_name, const double& joint_velocity) const;
bool verifyVelocityLimit(const std::string& joint_name, const double joint_velocity) const;

/**
* @brief verify position limit of single joint
* @param joint_name
* @param joint_position
* @return
*/
bool verifyPositionLimit(const std::string& joint_name, const double& joint_position) const;
bool verifyPositionLimit(const std::string& joint_name, const double joint_position) const;

private:
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr& scene,
const JointLimitsContainer& joint_limits, const KDL::Trajectory& trajectory,
const std::string& group_name, const std::string& link_name,
const Eigen::Translation3d& offset,
const std::map<std::string, double>& initial_joint_position, const double& sampling_time,
const std::map<std::string, double>& initial_joint_position, double sampling_time,
trajectory_msgs::JointTrajectory& joint_trajectory,
moveit_msgs::MoveItErrorCodes& error_code, bool check_self_collision = false);

Expand Down Expand Up @@ -202,12 +202,12 @@ bool isRobotStateStationary(const robot_state::RobotState& state, const std::str
* smallest index of trajectroy.
* @param index The intersection index which has to be determined.
*/
bool linearSearchIntersectionPoint(const std::string& link_name, const Eigen::Vector3d& center_position,
const double& r, const robot_trajectory::RobotTrajectoryPtr& traj, bool inverseOrder,
bool linearSearchIntersectionPoint(const std::string& link_name, const Eigen::Vector3d& center_position, const double r,
const robot_trajectory::RobotTrajectoryPtr& traj, bool inverseOrder,
std::size_t& index);

bool intersectionFound(const Eigen::Vector3d& p_center, const Eigen::Vector3d& p_current, const Eigen::Vector3d& p_next,
const double& r);
const double r);

/**
* @brief Checks if current robot state is in self collision.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,8 +137,8 @@ class TrajectoryGenerator
* The trap profile returns uses the longer distance of translational and
* rotational motion.
*/
std::unique_ptr<KDL::VelocityProfile> cartesianTrapVelocityProfile(const double& max_velocity_scaling_factor,
const double& max_acceleration_scaling_factor,
std::unique_ptr<KDL::VelocityProfile> cartesianTrapVelocityProfile(const double max_velocity_scaling_factor,
const double max_acceleration_scaling_factor,
const std::unique_ptr<KDL::Path>& path) const;

private:
Expand All @@ -158,7 +158,7 @@ class TrajectoryGenerator

virtual void plan(const planning_scene::PlanningSceneConstPtr& scene,
const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) = 0;
double sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) = 0;

private:
/**
Expand Down Expand Up @@ -246,9 +246,9 @@ class TrajectoryGenerator
/**
* @return True if scaling factor is valid, otherwise false.
*/
static bool isScalingFactorValid(const double& scaling_factor);
static void checkVelocityScaling(const double& scaling_factor);
static void checkAccelerationScaling(const double& scaling_factor);
static bool isScalingFactorValid(const double scaling_factor);
static void checkVelocityScaling(const double scaling_factor);
static void checkAccelerationScaling(const double scaling_factor);

/**
* @return True if ONE position + ONE orientation constraint given,
Expand All @@ -275,7 +275,7 @@ class TrajectoryGenerator
static constexpr double VELOCITY_TOLERANCE{ 1e-8 };
};

inline bool TrajectoryGenerator::isScalingFactorValid(const double& scaling_factor)
inline bool TrajectoryGenerator::isScalingFactorValid(const double scaling_factor)
{
return (scaling_factor > MIN_SCALING_FACTOR && scaling_factor <= MAX_SCALING_FACTOR);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class TrajectoryGeneratorCIRC : public TrajectoryGenerator
const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final;

void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
const MotionPlanInfo& plan_info, const double& sampling_time,
const MotionPlanInfo& plan_info, double sampling_time,
trajectory_msgs::JointTrajectory& joint_trajectory) override;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class TrajectoryGeneratorLIN : public TrajectoryGenerator
const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final;

void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
const MotionPlanInfo& plan_info, const double& sampling_time,
const MotionPlanInfo& plan_info, double sampling_time,
trajectory_msgs::JointTrajectory& joint_trajectory) override;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,11 +81,11 @@ class TrajectoryGeneratorPTP : public TrajectoryGenerator
* @param sampling_time
*/
void planPTP(const std::map<std::string, double>& start_pos, const std::map<std::string, double>& goal_pos,
trajectory_msgs::JointTrajectory& joint_trajectory, const double& velocity_scaling_factor,
const double& acceleration_scaling_factor, const double& sampling_time);
trajectory_msgs::JointTrajectory& joint_trajectory, const double velocity_scaling_factor,
const double acceleration_scaling_factor, double sampling_time);

void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
const MotionPlanInfo& plan_info, const double& sampling_time,
const MotionPlanInfo& plan_info, double sampling_time,
trajectory_msgs::JointTrajectory& joint_trajectory) override;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,13 +105,13 @@ std::map<std::string, JointLimit>::const_iterator JointLimitsContainer::end() co
return container_.end();
}

bool JointLimitsContainer::verifyVelocityLimit(const std::string& joint_name, const double& joint_velocity) const
bool JointLimitsContainer::verifyVelocityLimit(const std::string& joint_name, const double joint_velocity) const
{
return (!(hasLimit(joint_name) && getLimit(joint_name).has_velocity_limits &&
fabs(joint_velocity) > getLimit(joint_name).max_velocity));
}

bool JointLimitsContainer::verifyPositionLimit(const std::string& joint_name, const double& joint_position) const
bool JointLimitsContainer::verifyPositionLimit(const std::string& joint_name, const double joint_position) const
{
return (!(hasLimit(joint_name) && getLimit(joint_name).has_position_limits &&
(joint_position < getLimit(joint_name).min_position || joint_position > getLimit(joint_name).max_position)));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,8 @@ bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::validate
if (!pilz_industrial_motion_planner::isRobotStateEqual(
req.first_trajectory->getLastWayPoint(), req.second_trajectory->getFirstWayPoint(), req.group_name, EPSILON))
{
ROS_ERROR_STREAM("During blending the last point of the preceding and the first point of the succeding trajectory");
ROS_ERROR_STREAM(
"During blending the last point of the preceding and the first point of the succeding trajectory differ");
error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ bool pilz_industrial_motion_planner::generateJointTrajectory(
const planning_scene::PlanningSceneConstPtr& scene,
const pilz_industrial_motion_planner::JointLimitsContainer& joint_limits, const KDL::Trajectory& trajectory,
const std::string& group_name, const std::string& link_name, const Eigen::Translation3d& offset,
const std::map<std::string, double>& initial_joint_position, const double& sampling_time,
const std::map<std::string, double>& initial_joint_position, double sampling_time,
trajectory_msgs::JointTrajectory& joint_trajectory, moveit_msgs::MoveItErrorCodes& error_code,
bool check_self_collision)
{
Expand Down Expand Up @@ -509,7 +509,7 @@ bool pilz_industrial_motion_planner::isRobotStateStationary(const moveit::core::

bool pilz_industrial_motion_planner::linearSearchIntersectionPoint(const std::string& link_name,
const Eigen::Vector3d& center_position,
const double& r,
const double r,
const robot_trajectory::RobotTrajectoryPtr& traj,
bool inverseOrder, std::size_t& index)
{
Expand Down Expand Up @@ -547,7 +547,7 @@ bool pilz_industrial_motion_planner::linearSearchIntersectionPoint(const std::st

bool pilz_industrial_motion_planner::intersectionFound(const Eigen::Vector3d& p_center,
const Eigen::Vector3d& p_current, const Eigen::Vector3d& p_next,
const double& r)
const double r)
{
return ((p_current - p_center).norm() <= r) && ((p_next - p_center).norm() >= r);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ void TrajectoryGenerator::cmdSpecificRequestValidation(const planning_interface:
// to provide a command specific request validation.
}

void TrajectoryGenerator::checkVelocityScaling(const double& scaling_factor)
void TrajectoryGenerator::checkVelocityScaling(const double scaling_factor)
{
if (!isScalingFactorValid(scaling_factor))
{
Expand All @@ -86,7 +86,7 @@ void TrajectoryGenerator::checkVelocityScaling(const double& scaling_factor)
}
}

void TrajectoryGenerator::checkAccelerationScaling(const double& scaling_factor)
void TrajectoryGenerator::checkAccelerationScaling(const double scaling_factor)
{
if (!isScalingFactorValid(scaling_factor))
{
Expand Down Expand Up @@ -266,8 +266,8 @@ void TrajectoryGenerator::setFailureResponse(const ros::Time& planning_start,
}

std::unique_ptr<KDL::VelocityProfile>
TrajectoryGenerator::cartesianTrapVelocityProfile(const double& max_velocity_scaling_factor,
const double& max_acceleration_scaling_factor,
TrajectoryGenerator::cartesianTrapVelocityProfile(const double max_velocity_scaling_factor,
const double max_acceleration_scaling_factor,
const std::unique_ptr<KDL::Path>& path) const
{
std::unique_ptr<KDL::VelocityProfile> vp_trans(new KDL::VelocityProfile_Trap(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ void TrajectoryGeneratorCIRC::extractMotionPlanInfo(const planning_scene::Planni

void TrajectoryGeneratorCIRC::plan(const planning_scene::PlanningSceneConstPtr& scene,
const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory)
double sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory)
{
std::unique_ptr<KDL::Path> cart_path(setPathCIRC(plan_info));
std::unique_ptr<KDL::VelocityProfile> vel_profile(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ void TrajectoryGeneratorLIN::extractMotionPlanInfo(const planning_scene::Plannin

void TrajectoryGeneratorLIN::plan(const planning_scene::PlanningSceneConstPtr& scene,
const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory)
double sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory)
{
// create Cartesian path for lin
std::unique_ptr<KDL::Path> path(setPathLIN(plan_info.start_pose, plan_info.goal_pose));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@ TrajectoryGeneratorPTP::TrajectoryGeneratorPTP(const robot_model::RobotModelCons
void TrajectoryGeneratorPTP::planPTP(const std::map<std::string, double>& start_pos,
const std::map<std::string, double>& goal_pos,
trajectory_msgs::JointTrajectory& joint_trajectory,
const double& velocity_scaling_factor, const double& acceleration_scaling_factor,
const double& sampling_time)
const double velocity_scaling_factor, const double acceleration_scaling_factor,
double sampling_time)
{
// initialize joint names
for (const auto& item : goal_pos)
Expand Down Expand Up @@ -252,7 +252,7 @@ void TrajectoryGeneratorPTP::extractMotionPlanInfo(const planning_scene::Plannin

void TrajectoryGeneratorPTP::plan(const planning_scene::PlanningSceneConstPtr& /*scene*/,
const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory)
double sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory)
{
// plan the ptp trajectory
planPTP(plan_info.start_joint_position, plan_info.goal_joint_position, joint_trajectory,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -924,7 +924,7 @@ bool testutils::checkBlendingCartSpaceContinuity(const pilz_industrial_motion_pl
return true;
}

bool testutils::checkThatPointsInRadius(const std::string& link_name, const double& r, Eigen::Isometry3d& circ_pose,
bool testutils::checkThatPointsInRadius(const std::string& link_name, const double r, Eigen::Isometry3d& circ_pose,
const pilz_industrial_motion_planner::TrajectoryBlendResponse& res)
{
bool result = true;
Expand Down Expand Up @@ -1038,9 +1038,9 @@ bool testutils::getBlendTestData(const ros::NodeHandle& nh, const size_t& datase
bool testutils::generateTrajFromBlendTestData(
const planning_scene::PlanningSceneConstPtr& scene,
const std::shared_ptr<pilz_industrial_motion_planner::TrajectoryGenerator>& tg, const std::string& group_name,
const std::string& link_name, const testutils::BlendTestData& data, const double& sampling_time_1,
const double& sampling_time_2, planning_interface::MotionPlanResponse& res_1,
planning_interface::MotionPlanResponse& res_2, double& dis_1, double& dis_2)
const std::string& link_name, const testutils::BlendTestData& data, double sampling_time_1, double sampling_time_2,
planning_interface::MotionPlanResponse& res_1, planning_interface::MotionPlanResponse& res_2, double& dis_1,
double& dis_2)
{
const robot_model::RobotModelConstPtr robot_model = scene->getRobotModel();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -343,7 +343,7 @@ bool checkBlendingCartSpaceContinuity(const pilz_industrial_motion_planner::Traj
* @brief Checks if all points of the blending trajectory lie within the
* blending radius.
*/
bool checkThatPointsInRadius(const std::string& link_name, const double& r, Eigen::Isometry3d& circ_pose,
bool checkThatPointsInRadius(const std::string& link_name, const double r, Eigen::Isometry3d& circ_pose,
const pilz_industrial_motion_planner::TrajectoryBlendResponse& res);

/**
Expand Down Expand Up @@ -433,8 +433,8 @@ bool checkBlendResult(const pilz_industrial_motion_planner::TrajectoryBlendReque
bool generateTrajFromBlendTestData(const planning_scene::PlanningSceneConstPtr& scene,
const std::shared_ptr<pilz_industrial_motion_planner::TrajectoryGenerator>& tg,
const std::string& group_name, const std::string& link_name,
const BlendTestData& data, const double& sampling_time_1,
const double& sampling_time_2, planning_interface::MotionPlanResponse& res_lin_1,
const BlendTestData& data, double sampling_time_1, double sampling_time_2,
planning_interface::MotionPlanResponse& res_lin_1,
planning_interface::MotionPlanResponse& res_lin_2, double& dis_lin_1,
double& dis_lin_2);

Expand Down Expand Up @@ -472,7 +472,7 @@ checkCartesianRotationalPath(const robot_trajectory::RobotTrajectoryConstPtr& tr
const double rot_axis_tol = DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE,
const double acc_tol = DEFAULT_ACCELERATION_EQUALITY_TOLERANCE);

inline bool isMonotonouslyDecreasing(const std::vector<double>& vec, const double& tol)
inline bool isMonotonouslyDecreasing(const std::vector<double>& vec, const double tol)
{
return std::is_sorted(vec.begin(), vec.end(), [tol](double a, double b) {
return !(std::abs(a - b) < tol || a < b); // true -> a is ordered before b -> list is not sorted
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class TrajectoryFunctionsTestBase : public testing::TestWithParam<std::string>
* @param epsilon
* @return
*/
bool tfNear(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, const double& epsilon);
bool tfNear(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, const double epsilon);

protected:
// ros stuff
Expand Down Expand Up @@ -140,7 +140,7 @@ void TrajectoryFunctionsTestBase::SetUp()
}

bool TrajectoryFunctionsTestBase::tfNear(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2,
const double& epsilon)
const double epsilon)
{
for (std::size_t i = 0; i < 3; ++i)
for (std::size_t j = 0; j < 4; ++j)
Expand Down

0 comments on commit 50eb4e7

Please sign in to comment.