Go to the documentation of this file.
49 #include <boost/math/constants/constants.hpp>
52 constexpr
char LOGNAME[] =
"generate_state_database";
78 nh.
param<std::string>(
"state_space_parameterization",
"JointModel");
80 output_folder = nh.
param<std::string>(
"output_folder",
"constraint_approximations_database");
93 "Could not find valid constraint description in parameter '"
96 "Please upload correct correct constraint description or remap the parameter.");
121 scene->getCurrentStateNonConst().update();
129 scene->getCurrentState(), scene->getRobotModel()->getJointModelGroup(params.
planning_group)));
131 ompl_interface::ModelBasedPlanningContextPtr context =
ompl_interface.getPlanningContext(scene, req);
145 context->getConstraintsLibraryNonConst()->saveConstraintApproximations(params.
output_folder);
147 "Successfully generated Joint Space Constraint Approximation Database for constraint:\n"
165 int main(
int argc,
char** argv)
unsigned int max_explicit_points
static const std::string ROBOT_DESCRIPTION
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool setFromHandle(ros::NodeHandle &nh)
int main(int argc, char **argv)
void computeDB(const planning_scene::PlanningScenePtr &scene, struct GenerateStateDatabaseParameters ¶ms)
bool getParam(const std::string &key, bool &b) const
bool constructConstraints(XmlRpc::XmlRpcValue ¶ms, moveit_msgs::Constraints &constraints)
The MoveIt interface to OMPL.
moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
const planning_scene::PlanningScenePtr & getPlanningScene()
ConstraintApproximationPtr approx
#define ROS_FATAL_NAMED(name,...)
std::string resolveName(const std::string &name, bool remap=true) const
bool isEmpty(const geometry_msgs::Pose &msg)
const moveit::core::RobotModelConstPtr & getRobotModel() const
std::string planning_group
#define ROS_INFO_NAMED(name,...)
#define ROS_FATAL_STREAM_NAMED(name, args)
moveit_msgs::Constraints constraints
unsigned int edges_per_sample
double explicit_points_resolution
moveit_msgs::MotionPlanRequest MotionPlanRequest
std::string output_folder
ompl_interface::ConstraintApproximationConstructionOptions construction_opts
std::string state_space_parameterization
T param(const std::string ¶m_name, const T &default_val) const
#define ROS_INFO_STREAM_NAMED(name, args)
static const std::string CONSTRAINT_PARAMETER
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:09