Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/ompl_interface/ompl_interface.h>
00038 #include <moveit/robot_model_loader/robot_model_loader.h>
00039 #include <moveit/profiler/profiler.h>
00040
00041 #include <boost/math/constants/constants.hpp>
00042
00043 static const std::string ROBOT_DESCRIPTION = "robot_description";
00044
00045 moveit_msgs::Constraints getConstraints()
00046 {
00047 moveit_msgs::OrientationConstraint ocm;
00048 ocm.link_name = "r_wrist_roll_link";
00049 ocm.header.frame_id = "torso_lift_link";
00050 ocm.orientation.x = 0;
00051 ocm.orientation.y = 0;
00052 ocm.orientation.z = 0;
00053 ocm.orientation.w = 1.0;
00054 ocm.absolute_x_axis_tolerance = 0.1;
00055 ocm.absolute_y_axis_tolerance = 0.1;
00056 ocm.absolute_z_axis_tolerance = boost::math::constants::pi<double>();
00057 ocm.weight = 1.0;
00058 moveit_msgs::Constraints cmsg;
00059 cmsg.orientation_constraints.resize(1, ocm);
00060 cmsg.name = ocm.link_name + ":upright";
00061 return cmsg;
00062 }
00063
00064 void computeDB(const robot_model::RobotModelPtr& robot_model, unsigned int ns, unsigned int ne)
00065 {
00066 planning_scene::PlanningScenePtr ps(new planning_scene::PlanningScene(robot_model));
00067 ompl_interface::OMPLInterface ompl_interface(robot_model);
00068 moveit_msgs::Constraints c = getConstraints();
00069 ompl_interface::ConstraintApproximationConstructionOptions opt;
00070 opt.state_space_parameterization = "PoseModel";
00071 opt.samples = ns;
00072 opt.edges_per_sample = ne;
00073 opt.explicit_motions = true;
00074 opt.max_edge_length = 0.2;
00075 opt.explicit_points_resolution = 0.05;
00076 opt.max_explicit_points = 10;
00077
00078 ompl_interface.getConstraintsLibrary().addConstraintApproximation(c, "right_arm", ps, opt);
00079 ompl_interface.getConstraintsLibrary().saveConstraintApproximations("~/constraints_approximation_database");
00080 ROS_INFO("Done");
00081 }
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107 int main(int argc, char** argv)
00108 {
00109 ros::init(argc, argv, "construct_ompl_state_database", ros::init_options::AnonymousName);
00110
00111 ros::AsyncSpinner spinner(1);
00112 spinner.start();
00113
00114 unsigned int nstates = 1000;
00115 unsigned int nedges = 0;
00116
00117 if (argc > 1)
00118 try
00119 {
00120 nstates = boost::lexical_cast<unsigned int>(argv[1]);
00121 }
00122 catch (...)
00123 {
00124 }
00125
00126 if (argc > 2)
00127 try
00128 {
00129 nedges = boost::lexical_cast<unsigned int>(argv[2]);
00130 }
00131 catch (...)
00132 {
00133 }
00134
00135 robot_model_loader::RobotModelLoader rml(ROBOT_DESCRIPTION);
00136 computeDB(rml.getModel(), nstates, nedges);
00137
00138 ros::shutdown();
00139 return 0;
00140 }