Skip to content

Commit

Permalink
Cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe committed Dec 13, 2022
1 parent cc2bcf7 commit 92af883
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -207,8 +207,12 @@ class TimeOptimalTrajectoryGeneration : public TimeParameterization
const Eigen::VectorXd& max_velocity,
const Eigen::VectorXd& max_acceleration) const;

/// @brief Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid, if so.
bool checkMixedUnits(const moveit::core::JointModelGroup* group) const;
/**
* @brief Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid, if so.
* \param group The JointModelGroup to check.
* \return true if there are mixed joints.
*/
bool hasMixedJointTypes(const moveit::core::JointModelGroup* group) const;

const double path_tolerance_;
const double resample_dt_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1096,7 +1096,7 @@ bool TimeOptimalTrajectoryGeneration::doTimeParameterizationCalculations(robot_t
return false;
}

if (!checkMixedUnits(group))
if (hasMixedJointTypes(group))
{
RCLCPP_WARN(LOGGER, "There is a combination of revolute and prismatic joints in the robot model. TOTG's `path_tolerance` will not function correctly.");
}
Expand Down Expand Up @@ -1185,7 +1185,7 @@ bool TimeOptimalTrajectoryGeneration::doTimeParameterizationCalculations(robot_t
return true;
}

bool TimeOptimalTrajectoryGeneration::checkMixedUnits(const moveit::core::JointModelGroup* group) const
bool TimeOptimalTrajectoryGeneration::hasMixedJointTypes(const moveit::core::JointModelGroup* group) const
{
const std::vector<const moveit::core::JointModel*>& joint_models = group->getJointModels();

Expand All @@ -1199,8 +1199,6 @@ bool TimeOptimalTrajectoryGeneration::checkMixedUnits(const moveit::core::JointM
return joint_model->getType() == moveit::core::JointModel::JointType::REVOLUTE;
});

if (have_prismatic && have_revolute)
return false;
return true;
return have_prismatic && have_revolute;
}
} // namespace trajectory_processing

0 comments on commit 92af883

Please sign in to comment.