45 static const rclcpp::Logger
LOGGER =
46 rclcpp::get_logger(
"moveit_move_group_default_capabilities.plan_service_capability");
54 plan_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetMotionPlan>(
55 PLANNER_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
56 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Request>& req,
57 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Response>& res) {
58 return computePlanService(request_header, req, res);
62 bool MoveGroupPlanService::computePlanService(
const std::shared_ptr<rmw_request_id_t>& ,
63 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Request>& req,
64 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Response>& res)
66 RCLCPP_INFO(LOGGER,
"Received new planning service request...");
68 if (
static_cast<bool>(req->motion_plan_request.start_state.is_diff))
69 context_->planning_scene_monitor_->waitForCurrentRobotState(
context_->moveit_cpp_->getNode()->get_clock()->now());
70 context_->planning_scene_monitor_->updateFrameTransforms();
77 res->motion_plan_response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
88 catch (std::exception& ex)
90 RCLCPP_ERROR(LOGGER,
"Planning pipeline threw an exception: %s", ex.what());
91 res->motion_plan_response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
98 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
MoveGroupContextPtr context_
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
void initialize() override
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
const rclcpp::Logger LOGGER
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const