61 plan_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetMotionPlan>(
62 PLANNER_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
63 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Request>& req,
64 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Response>& res) {
65 return computePlanService(request_header, req, res);
69bool MoveGroupPlanService::computePlanService(
const std::shared_ptr<rmw_request_id_t>& ,
70 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Request>& req,
71 const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Response>& res)
73 RCLCPP_INFO(getLogger(),
"Received new planning service request...");
75 if (
static_cast<bool>(req->motion_plan_request.start_state.is_diff))
76 context_->planning_scene_monitor_->waitForCurrentRobotState(
context_->moveit_cpp_->getNode()->get_clock()->now());
77 context_->planning_scene_monitor_->updateFrameTransforms();
84 res->motion_plan_response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
94 RCLCPP_ERROR(getLogger(),
"Generating a plan with planning pipeline failed.");
95 mp_res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
99 catch (std::exception& ex)
101 RCLCPP_ERROR(
getLogger(),
"Planning pipeline threw an exception: %s", ex.what());
102 res->motion_plan_response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
109#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.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Response to a planning query.
moveit::core::MoveItErrorCode error_code
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
Construct a ROS message from struct data.