39 #include <rclcpp/clock.hpp>
40 #include <rclcpp/duration.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/time.hpp>
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_constraint_samplers.constraint_sampler_tools");
50 const planning_scene::PlanningSceneConstPtr&
scene,
const std::string&
group,
51 const std::string& link_name,
unsigned int sample_count,
52 visualization_msgs::msg::MarkerArray& markers)
55 link_name, sample_count, markers);
59 const planning_scene::PlanningSceneConstPtr&
scene,
const std::string&
group)
62 scene->getCurrentState());
69 RCLCPP_ERROR(LOGGER,
"No sampler specified for counting samples per second");
73 unsigned long int valid = 0;
74 unsigned long int total = 0;
75 rclcpp::Time end = rclcpp::Clock().now() + rclcpp::Duration::from_seconds(1);
78 static const unsigned int N = 10;
80 for (
unsigned int i = 0; i < N; ++i)
82 if (sampler->sample(ks, 1))
85 }
while (rclcpp::Clock().now() < end);
86 return (
double)valid / (double)total;
90 const std::string& link_name,
unsigned int sample_count,
91 visualization_msgs::msg::MarkerArray& markers)
95 RCLCPP_ERROR(LOGGER,
"No sampler specified for visualizing distribution of samples");
102 std_msgs::msg::ColorRGBA color;
107 for (
unsigned int i = 0; i < sample_count; ++i)
109 if (!sampler->sample(ks))
112 visualization_msgs::msg::Marker mk;
113 mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
114 mk.header.frame_id = sampler->getJointModelGroup()->getParentModel().getModelFrame();
115 mk.ns =
"constraint_samples";
117 mk.type = visualization_msgs::msg::Marker::SPHERE;
118 mk.action = visualization_msgs::msg::Marker::ADD;
119 mk.pose.position.x = pos.x();
120 mk.pose.position.y = pos.y();
121 mk.pose.position.z = pos.z();
122 mk.pose.orientation.w = 1.0;
123 mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
125 mk.lifetime = rclcpp::Duration::from_seconds(30);
126 markers.markers.push_back(mk);
static ConstraintSamplerPtr selectDefaultSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr)
Default logic to select a ConstraintSampler given a constraints message.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
double countSamplesPerSecond(const ConstraintSamplerPtr &sampler, const moveit::core::RobotState &reference_state)
void visualizeDistribution(const ConstraintSamplerPtr &sampler, const moveit::core::RobotState &reference_state, const std::string &link_name, unsigned int sample_count, visualization_msgs::msg::MarkerArray &markers)
Vec3fX< details::Vec3Data< double > > Vector3d