Skip to content

Commit

Permalink
Revert "Deprecate ugly function signature"
Browse files Browse the repository at this point in the history
This reverts commit 57a85c8.
  • Loading branch information
sjahr committed Aug 26, 2024
1 parent 57a85c8 commit 598cc0c
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -246,17 +246,13 @@ class RobotModel
bool hasLinkModel(const std::string& name) const;

/** \brief Get a link by its name. Output error and return nullptr when the link is missing. */
const LinkModel* getLinkModel(const std::string& link) const;
[[deprecated("Use getLinkModel(const std::string& name) instead.")]] const LinkModel*
getLinkModel(const std::string& link, bool* has_link) const;
const LinkModel* getLinkModel(const std::string& link, bool* has_link = nullptr) const;

/** \brief Get a link by its index. Output error and return nullptr when the link is missing. */
const LinkModel* getLinkModel(size_t index) const;

/** \brief Get a link by its name. Output error and return nullptr when the link is missing. */
LinkModel* getLinkModel(const std::string& link);
[[deprecated("Use getLinkModel(const std::string& name) instead.")]] LinkModel*
getLinkModel(const std::string& link, bool* has_link = nullptr);
LinkModel* getLinkModel(const std::string& link, bool* has_link = nullptr);

/** \brief Get the latest link upwards the kinematic tree, which is only connected via fixed joints
*
Expand Down
17 changes: 7 additions & 10 deletions moveit_core/robot_model/src/robot_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1331,8 +1331,7 @@ JointModel* RobotModel::getJointModel(const std::string& name)

const LinkModel* RobotModel::getLinkModel(const std::string& name, bool* has_link) const
{
*has_link = false;
return const_cast<RobotModel*>(this)->getLinkModel(name);
return const_cast<RobotModel*>(this)->getLinkModel(name, has_link);
}

const LinkModel* RobotModel::getLinkModel(size_t index) const
Expand All @@ -1348,22 +1347,20 @@ const LinkModel* RobotModel::getLinkModel(size_t index) const

LinkModel* RobotModel::getLinkModel(const std::string& name, bool* has_link)
{
if (has_link)
*has_link = true; // Start out optimistic
LinkModelMap::const_iterator it = link_model_map_.find(name);
if (it != link_model_map_.end())
{
return it->second;

if (has_link)
{
*has_link = false; // Report failure via argument
}
RCLCPP_ERROR(getLogger(), "Link '%s' not found in model '%s'", name.c_str(), model_name_.c_str());
return nullptr;
}

const LinkModel* getLinkModel(const std::string& link, bool* has_link) const
{
RCLCPP_ERROR(getLogger(), "'has_link' argument is deprecated. Use getLinkModel(const std::string& name) instead.");
*has_link = false;
return getLinkModel(link);
}

const LinkModel* RobotModel::getRigidlyConnectedParentLinkModel(const LinkModel* link)
{
if (!link)
Expand Down
3 changes: 1 addition & 2 deletions moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1344,9 +1344,8 @@ const Eigen::Isometry3d& RobotState::getFrameInfo(const std::string& frame_id, c
frame_found = true;
return IDENTITY_TRANSFORM;
}
if ((robot_link = robot_model_->getLinkModel(frame_id)))
if ((robot_link = robot_model_->getLinkModel(frame_id, &frame_found)))
{
frame_found = true;
assert(checkLinkTransforms());
return global_link_transforms_[robot_link->getLinkIndex()];
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -389,8 +389,9 @@ bool IKFastKinematicsPlugin::computeRelativeTransform(const std::string& from, c
robot_state = std::make_shared<RobotState>(robot_model_);
robot_state->setToDefaultValues();

auto* from_link = robot_model_->getLinkModel(from);
auto* to_link = robot_model_->getLinkModel(to);
bool has_link; // to suppress RCLCPP_ERRORs for non-existent frames
auto* from_link = robot_model_->getLinkModel(from, &has_link);
auto* to_link = robot_model_->getLinkModel(to, &has_link);
if (!from_link || !to_link)
return false;

Expand Down

0 comments on commit 598cc0c

Please sign in to comment.