62 load_geometry_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::LoadGeometryFromFile>(
63 LOAD_GEOMETRY_FROM_FILE_SERVICE_NAME,
64 [
this](
const std::shared_ptr<moveit_msgs::srv::LoadGeometryFromFile::Request>& req,
65 const std::shared_ptr<moveit_msgs::srv::LoadGeometryFromFile::Response>& res) {
66 std::ifstream file(req->file_path_and_name);
69 RCLCPP_ERROR(
getLogger(),
"Unable to open file %s for loading CollisionObjects",
70 req->file_path_and_name.c_str());
75 locked_ps->loadGeometryFromStream(file);
83 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
Move group capability to save CollisionObjects in a PlanningScene to a .scene file.
void initialize() override
Initializes service when plugin is loaded.
LoadGeometryFromFileService()
MoveGroupContextPtr context_
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.