38 #include <class_loader/class_loader.hpp>
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 #include <rclcpp/node.hpp>
42 #include <rclcpp/parameter_value.hpp>
46 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.fix_workspace_bounds");
53 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
57 workspace_extent_ /= 2.0;
62 return "Fix Workspace Bounds";
67 std::vector<std::size_t>& )
const override
70 const moveit_msgs::msg::WorkspaceParameters& wparams = req.workspace_parameters;
71 if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
72 wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
73 wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
75 RCLCPP_DEBUG(LOGGER,
"It looks like the planning volume was not specified. Using default values.");
77 moveit_msgs::msg::WorkspaceParameters& default_wp = req2.workspace_parameters;
78 default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z = -workspace_extent_;
79 default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z = workspace_extent_;
87 rclcpp::Node::SharedPtr node_;
88 double workspace_extent_;
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
static const std::string WBOUNDS_PARAM_NAME
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string ¶meter_namespace, const std::string ¶meter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)