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/constraint_samplers/constraint_sampler_tools.h>
00038 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
00039
00040 void constraint_samplers::visualizeDistribution(const moveit_msgs::Constraints& constr,
00041 const planning_scene::PlanningSceneConstPtr& scene,
00042 const std::string& group, const std::string& link_name,
00043 unsigned int sample_count, visualization_msgs::MarkerArray& markers)
00044 {
00045 visualizeDistribution(ConstraintSamplerManager::selectDefaultSampler(scene, group, constr), scene->getCurrentState(),
00046 link_name, sample_count, markers);
00047 }
00048
00049 double constraint_samplers::countSamplesPerSecond(const moveit_msgs::Constraints& constr,
00050 const planning_scene::PlanningSceneConstPtr& scene,
00051 const std::string& group)
00052 {
00053 return countSamplesPerSecond(ConstraintSamplerManager::selectDefaultSampler(scene, group, constr),
00054 scene->getCurrentState());
00055 }
00056
00057 double constraint_samplers::countSamplesPerSecond(const ConstraintSamplerPtr& sampler,
00058 const robot_state::RobotState& reference_state)
00059 {
00060 if (!sampler)
00061 {
00062 logError("No sampler specified for counting samples per second");
00063 return 0.0;
00064 }
00065 robot_state::RobotState ks(reference_state);
00066 unsigned long int valid = 0;
00067 unsigned long int total = 0;
00068 ros::WallTime end = ros::WallTime::now() + ros::WallDuration(1.0);
00069 do
00070 {
00071 static const unsigned int n = 10;
00072 total += n;
00073 for (unsigned int i = 0; i < n; ++i)
00074 {
00075 if (sampler->sample(ks, 1))
00076 valid++;
00077 }
00078 } while (ros::WallTime::now() < end);
00079 return (double)valid / (double)total;
00080 }
00081
00082 void constraint_samplers::visualizeDistribution(const ConstraintSamplerPtr& sampler,
00083 const robot_state::RobotState& reference_state,
00084 const std::string& link_name, unsigned int sample_count,
00085 visualization_msgs::MarkerArray& markers)
00086 {
00087 if (!sampler)
00088 {
00089 logError("No sampler specified for visualizing distribution of samples");
00090 return;
00091 }
00092 const robot_state::LinkModel* lm = reference_state.getLinkModel(link_name);
00093 if (!lm)
00094 return;
00095 robot_state::RobotState ks(reference_state);
00096 std_msgs::ColorRGBA color;
00097 color.r = 1.0f;
00098 color.g = 0.0f;
00099 color.b = 0.0f;
00100 color.a = 1.0f;
00101 for (unsigned int i = 0; i < sample_count; ++i)
00102 {
00103 if (!sampler->sample(ks))
00104 continue;
00105 const Eigen::Vector3d& pos = ks.getGlobalLinkTransform(lm).translation();
00106 visualization_msgs::Marker mk;
00107 mk.header.stamp = ros::Time::now();
00108 mk.header.frame_id = sampler->getJointModelGroup()->getParentModel().getModelFrame();
00109 mk.ns = "constraint_samples";
00110 mk.id = i;
00111 mk.type = visualization_msgs::Marker::SPHERE;
00112 mk.action = visualization_msgs::Marker::ADD;
00113 mk.pose.position.x = pos.x();
00114 mk.pose.position.y = pos.y();
00115 mk.pose.position.z = pos.z();
00116 mk.pose.orientation.w = 1.0;
00117 mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
00118 mk.color = color;
00119 mk.lifetime = ros::Duration(30.0);
00120 markers.markers.push_back(mk);
00121 }
00122 }