41 #include <class_loader/class_loader.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
47 #include <default_request_adapter_parameters.hpp>
60 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
62 param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);
67 return std::string(
"ValidateWorkspaceBounds");
74 const moveit_msgs::msg::WorkspaceParameters& wparams = req.workspace_parameters;
75 if (std::abs(wparams.min_corner.x) < std::numeric_limits<double>::epsilon() &&
76 std::abs(wparams.min_corner.y) < std::numeric_limits<double>::epsilon() &&
77 std::abs(wparams.min_corner.z) < std::numeric_limits<double>::epsilon() &&
78 std::abs(wparams.max_corner.x) < std::numeric_limits<double>::epsilon() &&
79 std::abs(wparams.max_corner.y) < std::numeric_limits<double>::epsilon() &&
80 std::abs(wparams.max_corner.z) < std::numeric_limits<double>::epsilon())
82 RCLCPP_WARN(logger_,
"It looks like the planning volume was not specified. Using default values.");
83 moveit_msgs::msg::WorkspaceParameters& default_wp = req.workspace_parameters;
84 const auto params = param_listener_->get_params();
86 default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z =
87 -params.default_workspace_bounds / 2.0;
88 default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z =
89 params.default_workspace_bounds / 2.0;
95 std::unique_ptr<default_request_adapter_parameters::ParamListener> param_listener_;
96 rclcpp::Logger logger_;
If not specified by the planning request, this request adapter will specify a default workspace for p...
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &, planning_interface::MotionPlanRequest &req) const override
Adapt the planning request.
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
ValidateWorkspaceBounds()
std::string getDescription() const override
Get a description of this adapter.
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Concept in MoveIt which can be used to modify the planning problem(pre-processing) in a planning pipe...
rclcpp::Logger getLogger()
Main namespace for MoveIt.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)