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

Do not pass and return simple types by const ref #2453

Merged
merged 7 commits into from Oct 24, 2023
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.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
31 changes: 14 additions & 17 deletions moveit_core/collision_detection/src/collision_octomap_filter.cpp
Expand Up @@ -48,21 +48,19 @@
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection.collision_octomap_filter");

// forward declarations
bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const double& spacing, const double& iso_value,
const double& r_multiple, const octomath::Vector3& contact_point,
octomath::Vector3& normal, double& depth, bool estimate_depth);
bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, double spacing, double iso_value,
double r_multiple, const octomath::Vector3& contact_point, octomath::Vector3& normal,
double& depth, bool estimate_depth);

bool findSurface(const octomap::point3d_list& cloud, const double& spacing, const double& iso_value,
const double& r_multiple, const octomath::Vector3& seed, octomath::Vector3& surface_point,
octomath::Vector3& normal);
bool findSurface(const octomap::point3d_list& cloud, double spacing, double iso_value, double r_multiple,
const octomath::Vector3& seed, octomath::Vector3& surface_point, octomath::Vector3& normal);

bool sampleCloud(const octomap::point3d_list& cloud, const double& spacing, const double& r_multiple,
bool sampleCloud(const octomap::point3d_list& cloud, double spacing, double r_multiple,
const octomath::Vector3& position, double& intensity, octomath::Vector3& gradient);

int collision_detection::refineContactNormals(const World::ObjectConstPtr& object, CollisionResult& res,
const double cell_bbx_search_distance,
const double allowed_angle_divergence, const bool estimate_depth,
const double iso_value, const double metaball_radius_multiple)
double cell_bbx_search_distance, double allowed_angle_divergence,
bool estimate_depth, double iso_value, double metaball_radius_multiple)
{
if (!object)
{
Expand Down Expand Up @@ -170,9 +168,9 @@ int collision_detection::refineContactNormals(const World::ObjectConstPtr& objec
return modified;
}

bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const double& spacing, const double& iso_value,
const double& r_multiple, const octomath::Vector3& contact_point,
octomath::Vector3& normal, double& depth, const bool estimate_depth)
bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, double spacing, double iso_value,
double r_multiple, const octomath::Vector3& contact_point, octomath::Vector3& normal,
double& depth, bool estimate_depth)
{
if (estimate_depth)
{
Expand Down Expand Up @@ -207,9 +205,8 @@ bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const doub
// This algorithm is from Salisbury & Tarr's 1997 paper. It will find the
// closest point on the surface starting from a seed point that is close by
// following the direction of the field gradient.
bool findSurface(const octomap::point3d_list& cloud, const double& spacing, const double& iso_value,
const double& r_multiple, const octomath::Vector3& seed, octomath::Vector3& surface_point,
octomath::Vector3& normal)
bool findSurface(const octomap::point3d_list& cloud, double spacing, double iso_value, double r_multiple,
const octomath::Vector3& seed, octomath::Vector3& surface_point, octomath::Vector3& normal)
{
octomath::Vector3 p = seed, dp, gs;
const int iterations = 10;
Expand All @@ -233,7 +230,7 @@ bool findSurface(const octomap::point3d_list& cloud, const double& spacing, cons
// return p;
}

bool sampleCloud(const octomap::point3d_list& cloud, const double& spacing, const double& r_multiple,
bool sampleCloud(const octomap::point3d_list& cloud, double spacing, double r_multiple,
const octomath::Vector3& position, double& intensity, octomath::Vector3& gradient)
{
intensity = 0.f;
Expand Down
6 changes: 3 additions & 3 deletions moveit_core/constraint_samplers/test/pr2_arm_ik.cpp
Expand Up @@ -198,7 +198,7 @@ void PR2ArmIK::getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info)
info = solver_info_;
}

void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double& t1_in,
void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, double t1_in,
std::vector<std::vector<double> >& solution) const
{
// t1 = shoulder/turret pan is specified
Expand Down Expand Up @@ -463,7 +463,7 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
}
}

void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double& t3,
void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double t3,
std::vector<std::vector<double> >& solution) const
{
std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF, 0.0);
Expand Down Expand Up @@ -779,7 +779,7 @@ bool PR2ArmIK::checkJointLimits(const std::vector<double>& joint_values) const
return true;
}

bool PR2ArmIK::checkJointLimits(const double& joint_value, const int& joint_num) const
bool PR2ArmIK::checkJointLimits(const double joint_value, const int joint_num) const
{
double jv;
if (continuous_joint_[joint_num])
Expand Down
10 changes: 5 additions & 5 deletions moveit_core/constraint_samplers/test/pr2_arm_ik.h
Expand Up @@ -58,7 +58,7 @@ inline double distance(const urdf::Pose& transform)
transform.position.z * transform.position.z);
}

inline bool solveQuadratic(const double& a, const double& b, const double& c, double* x1, double* x2)
inline bool solveQuadratic(double a, double b, double c, double* x1, double* x2)
{
double discriminant = b * b - 4 * a * c;
if (fabs(a) < IK_EPS)
Expand Down Expand Up @@ -88,7 +88,7 @@ inline bool solveQuadratic(const double& a, const double& b, const double& c, do
}
}

inline bool solveCosineEqn(const double& a, const double& b, const double& c, double& soln1, double& soln2)
inline bool solveCosineEqn(double a, double b, double c, double& soln1, double& soln2)
{
double theta1 = atan2(b, a);
double denom = sqrt(a * a + b * b);
Expand Down Expand Up @@ -140,15 +140,15 @@ class PR2ArmIK
@param Input pose for end-effector
@param Initial guess for shoulder pan angle
*/
void computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double& shoulder_pan_initial_guess,
void computeIKShoulderPan(const Eigen::Isometry3f& g_in, double shoulder_pan_initial_guess,
std::vector<std::vector<double> >& solution) const;

/**
@brief compute IK based on an initial guess for the shoulder roll angle.
h @param Input pose for end-effector
@param Initial guess for shoulder roll angle
*/
void computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double& shoulder_roll_initial_guess,
void computeIKShoulderRoll(const Eigen::Isometry3f& g_in, double shoulder_roll_initial_guess,
std::vector<std::vector<double> >& solution) const;

// std::vector<std::vector<double> > solution_ik_;/// a vector of ik solutions
Expand All @@ -172,7 +172,7 @@ class PR2ArmIK

bool checkJointLimits(const std::vector<double>& joint_values) const;

bool checkJointLimits(const double& joint_value, const int& joint_num) const;
bool checkJointLimits(double joint_value, int joint_num) const;

Eigen::Isometry3f grhs_, gf_, home_inv_;

Expand Down
Expand Up @@ -50,7 +50,7 @@ namespace pr2_arm_kinematics
{
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_constraint_samplers.test.pr2_arm_kinematics_plugin");

bool PR2ArmIKSolver::getCount(int& count, const int& max_count, const int& min_count)
bool PR2ArmIKSolver::getCount(int& count, int max_count, int min_count)
{
if (count > 0)
{
Expand Down Expand Up @@ -87,8 +87,7 @@ bool PR2ArmIKSolver::getCount(int& count, const int& max_count, const int& min_c
}

PR2ArmIKSolver::PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
const std::string& tip_frame_name, const double& search_discretization_angle,
const int& free_angle)
const std::string& tip_frame_name, double search_discretization_angle, int free_angle)
: ChainIkSolverPos()
{
search_discretization_angle_ = search_discretization_angle;
Expand Down Expand Up @@ -160,7 +159,7 @@ int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_i
}

int PR2ArmIKSolver::cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out,
const double& timeout)
double timeout)
{
const bool verbose = false;
KDL::JntArray q_init = q_in;
Expand Down
Expand Up @@ -80,7 +80,7 @@ class PR2ArmIKSolver : public KDL::ChainIkSolverPos
* to return multiple solutions from an inverse kinematics computation.
*/
PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
const std::string& tip_frame_name, const double& search_discretization_angle, const int& free_angle);
const std::string& tip_frame_name, double search_discretization_angle, int free_angle);

~PR2ArmIKSolver() override{};

Expand All @@ -98,15 +98,15 @@ class PR2ArmIKSolver : public KDL::ChainIkSolverPos

int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out) override;

int cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out, const double& timeout);
int cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out, double timeout);

void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& response)
{
pr2_arm_ik_.getSolverInfo(response);
}

private:
bool getCount(int& count, const int& max_count, const int& min_count);
bool getCount(int& count, int max_count, int min_count);

double search_discretization_angle_;

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/kinematics_base/src/kinematics_base.cpp
Expand Up @@ -95,7 +95,7 @@ bool KinematicsBase::initialize(const rclcpp::Node::SharedPtr& /*node*/,

bool KinematicsBase::setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices)
{
for (const unsigned int& redundant_joint_index : redundant_joint_indices)
for (unsigned int redundant_joint_index : redundant_joint_indices)
{
if (redundant_joint_index >= getJointNames().size())
{
Expand Down
Expand Up @@ -129,7 +129,7 @@ class KinematicsMetrics
penalty_multiplier_ = fabs(multiplier);
}

const double& getPenaltyMultiplier() const
double getPenaltyMultiplier() const
{
return penalty_multiplier_;
}
Expand Down
Expand Up @@ -300,7 +300,7 @@ class RobotTrajectory
* @param The waypoint index after (or equal to) the supplied duration.
* @param 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(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
Expand Up @@ -490,7 +490,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(double duration, int& before, int& after,
double& blend) const
{
if (duration < 0.0)
Expand Down
Expand Up @@ -64,9 +64,9 @@ std::size_t trajectoryWaypointCount(const moveit_msgs::msg::RobotTrajectory& tra
* \param [in] min_angle_change The minimum angle change to use for time parameterization (default: 0.001).
* \return True if time parameterization was successful, false otherwise.
*/
bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory, const double& velocity_scaling_factor,
const double& acceleration_scaling_factor, const double path_tolerance = 0.1,
const double resample_dt = 0.1, const double min_angle_change = 0.001);
bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
double acceleration_scaling_factor, double path_tolerance = 0.1,
double resample_dt = 0.1, double min_angle_change = 0.001);
/**
* \brief Applies Ruckig smoothing to a robot trajectory.
* \param [in,out] trajectory The robot trajectory to be smoothed.
Expand All @@ -76,7 +76,7 @@ bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory
* \param [in] overshoot_threshold The maximum allowed overshoot during smoothing (default: 0.01).
* \return True if smoothing was successful, false otherwise.
*/
bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory& trajectory, const double& velocity_scaling_factor,
const double& acceleration_scaling_factor, const bool mitigate_overshoot = false,
const double overshoot_threshold = 0.01);
bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
double acceleration_scaling_factor, bool mitigate_overshoot = false,
double overshoot_threshold = 0.01);
} // namespace trajectory_processing
11 changes: 5 additions & 6 deletions moveit_core/trajectory_processing/src/trajectory_tools.cpp
Expand Up @@ -48,16 +48,15 @@ std::size_t trajectoryWaypointCount(const moveit_msgs::msg::RobotTrajectory& tra
{
return std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
}
bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory, const double& velocity_scaling_factor,
const double& acceleration_scaling_factor, const double path_tolerance,
const double resample_dt, const double min_angle_change)
bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
double acceleration_scaling_factor, double path_tolerance, double resample_dt,
double min_angle_change)
{
TimeOptimalTrajectoryGeneration totg(path_tolerance, resample_dt, min_angle_change);
return totg.computeTimeStamps(trajectory, velocity_scaling_factor, acceleration_scaling_factor);
}
bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory& trajectory, const double& velocity_scaling_factor,
const double& acceleration_scaling_factor, const bool mitigate_overshoot,
const double overshoot_threshold)
bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
double acceleration_scaling_factor, bool mitigate_overshoot, double overshoot_threshold)
{
RuckigSmoothing time_param;
return time_param.applySmoothing(trajectory, velocity_scaling_factor, acceleration_scaling_factor, mitigate_overshoot,
Expand Down
Expand Up @@ -353,7 +353,7 @@ class IKFastKinematicsPlugin : public kinematics::KinematicsBase
double enforceLimits(double val, double min, double max) const;

void fillFreeParams(int count, int* array);
bool getCount(int& count, const int& max_count, const int& min_count) const;
bool getCount(int& count, int max_count, int min_count) const;

/**
* @brief samples the designated redundant joint using the chosen discretization method
Expand Down Expand Up @@ -728,7 +728,7 @@ void IKFastKinematicsPlugin::fillFreeParams(int count, int* array)
free_params_.push_back(array[i]);
}

bool IKFastKinematicsPlugin::getCount(int& count, const int& max_count, const int& min_count) const
bool IKFastKinematicsPlugin::getCount(int& count, int max_count, int min_count) const
{
if (count > 0)
{
Expand Down
Expand Up @@ -154,7 +154,7 @@ bool SrvKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& re

bool SrvKinematicsPlugin::isRedundantJoint(unsigned int index) const
{
for (const unsigned int& redundant_joint_indice : redundant_joint_indices_)
for (unsigned int redundant_joint_indice : redundant_joint_indices_)
{
if (redundant_joint_indice == index)
return true;
Expand Down
Expand Up @@ -446,7 +446,7 @@ ompl::base::ConstraintPtr createOMPLConstraints(const moveit::core::RobotModelCo
* https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2016/RD2016script.pdf
* Eq. 2.107
* */
inline Eigen::Matrix3d angularVelocityToAngleAxis(const double& angle, const Eigen::Ref<const Eigen::Vector3d>& axis)
inline Eigen::Matrix3d angularVelocityToAngleAxis(double angle, const Eigen::Ref<const Eigen::Vector3d>& axis)
{
double t{ std::abs(angle) };
Eigen::Matrix3d r_skew;
Expand Down
Expand Up @@ -126,7 +126,7 @@ bool verifySampleJointLimits(const std::map<std::string, double>& position_last,
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 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::msg::JointTrajectory& joint_trajectory,
moveit_msgs::msg::MoveItErrorCodes& error_code, bool check_self_collision = false);

Expand Down Expand Up @@ -195,12 +195,12 @@ bool isRobotStateStationary(const moveit::core::RobotState& state, const std::st
* 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);
double r);

/**
* @brief Checks if current robot state is in self collision.
Expand Down