Skip to content

Commit

Permalink
Get robot description from topic in GetUrdfService (#2681)
Browse files Browse the repository at this point in the history
  • Loading branch information
Abishalini authored Feb 13, 2024
1 parent ce40e08 commit ab48a49
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -78,16 +78,14 @@ void GetUrdfService::initialize()
res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
return;
}
// Get robot description string
std::string full_urdf_string;
context_->moveit_cpp_->getNode()->get_parameter_or("robot_description", full_urdf_string, std::string(""));

// Check if string is empty
std::string full_urdf_string =
context_->moveit_cpp_->getPlanningSceneMonitor()->getRobotModelLoader()->getRDFLoader()->getURDFString();

// Check if robot description string is empty
if (full_urdf_string.empty())
{
const auto error_string =
std::string("Couldn't load the urdf from parameter server. Is the '/robot_description' parameter "
"initialized?");
const auto error_string = std::string("Couldn't get the robot description string from MoveItCpp");
RCLCPP_ERROR(getLogger(), "%s", error_string.c_str());
res->error_code.message = error_string;
res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,12 @@ class RDFLoader
return ros_name_;
}

/** @brief Get the URDF string*/
const std::string& getURDFString() const
{
return urdf_string_;
}

/** @brief Get the parsed URDF model*/
const urdf::ModelInterfaceSharedPtr& getURDF() const
{
Expand Down

0 comments on commit ab48a49

Please sign in to comment.