66 return "Fix Workspace Bounds";
71 std::vector<std::size_t>& )
const override
74 const moveit_msgs::WorkspaceParameters& wparams = req.workspace_parameters;
75 if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
76 wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
77 wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
79 ROS_DEBUG(
"It looks like the planning volume was not specified. Using default values.");
81 moveit_msgs::WorkspaceParameters& default_wp = req2.workspace_parameters;
82 default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z = -
workspace_extent_;
83 default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z =
workspace_extent_;