48#include <boost/math/constants/constants.hpp>
51static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.planners_ompl.generate_state_database");
53static const std::string ROBOT_DESCRIPTION =
"robot_description";
55static const std::string CONSTRAINT_PARAMETER =
"constraints";
57static bool getUintParameterOr(
const rclcpp::Node::SharedPtr& node,
const std::string& param_name,
58 size_t&& result_value,
const size_t default_value)
61 if (node->get_parameter(param_name, param_value))
65 result_value =
static_cast<size_t>(param_value);
69 RCLCPP_WARN_STREAM(LOGGER,
"Value for parameter '" << param_name
70 <<
"' must be positive\n"
71 "Using back to default value:"
75 result_value = default_value;
100 std::string(
"JointModel"));
102 node->get_parameter_or(
"output_folder",
output_folder, std::string(
"constraint_approximation_database"));
106 RCLCPP_FATAL(LOGGER,
"~planning_group parameter has to be specified.");
112 RCLCPP_FATAL_STREAM(LOGGER,
113 "Could not find valid constraint description in parameter '"
114 << node->get_fully_qualified_name() <<
'.' << CONSTRAINT_PARAMETER
116 "Please upload correct correct constraint description or remap the parameter.");
138void computeDB(
const rclcpp::Node::SharedPtr& node,
const planning_scene::PlanningScenePtr& scene,
142 scene->getCurrentStateNonConst().update();
150 scene->getCurrentState(), scene->getRobotModel()->getJointModelGroup(params.
planning_group)));
152 ompl_interface::ModelBasedPlanningContextPtr context =
ompl_interface.getPlanningContext(scene, req);
154 RCLCPP_INFO_STREAM(LOGGER,
"Generating Joint Space Constraint Approximation Database for constraint:\n"
163 RCLCPP_FATAL(LOGGER,
"Failed to generate approximation.");
166 context->getConstraintsLibraryNonConst()->saveConstraintApproximations(params.
output_folder);
167 RCLCPP_INFO_STREAM(LOGGER,
"Successfully generated Joint Space Constraint Approximation Database for constraint:\n"
169 RCLCPP_INFO_STREAM(LOGGER,
"The database has been saved in your local folder '" << params.
output_folder <<
'\'');
200 rclcpp::init(argc, argv);
201 rclcpp::NodeOptions opt;
202 opt.automatically_declare_parameters_from_overrides(
true);
203 std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared(
"generate_state_database", opt);
215 RCLCPP_INFO(LOGGER,
"Requesting current planning scene to generate database");
218 RCLCPP_FATAL(LOGGER,
"Abort. The current scene could not be retrieved.");
225 RCLCPP_FATAL(LOGGER,
"Abort. Constraint description is an empty set of constraints.");
PlanningSceneMonitor Subscribes to the topic planning_scene.
const moveit::core::RobotModelConstPtr & getRobotModel() const
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Request a full planning scene state using a service call Be careful not to use this in conjunction wi...
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
int main(int argc, char **argv)
void computeDB(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, struct GenerateStateDatabaseParameters ¶ms)
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
bool constructConstraints(const rclcpp::Node::SharedPtr &node, const std::string &constraints_param, moveit_msgs::msg::Constraints &constraints)
extract constraint message from node parameters.
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
The MoveIt interface to OMPL.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
ompl_interface::ConstraintApproximationConstructionOptions construction_opts
std::string output_folder
std::string planning_group
bool setFromNode(const rclcpp::Node::SharedPtr &node)
moveit_msgs::msg::Constraints constraints
std::string state_space_parameterization
double explicit_points_resolution
unsigned int edges_per_sample
unsigned int max_explicit_points
ConstraintApproximationPtr approx