moveit2
The MoveIt Motion Planning Framework for ROS 2.
constraint_sampler_tools.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
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>
44 
45 namespace constraint_samplers
46 {
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_constraint_samplers.constraint_sampler_tools");
48 
49 void visualizeDistribution(const moveit_msgs::msg::Constraints& constr,
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)
53 {
55  link_name, sample_count, markers);
56 }
57 
58 double countSamplesPerSecond(const moveit_msgs::msg::Constraints& constr,
59  const planning_scene::PlanningSceneConstPtr& scene, const std::string& group)
60 {
62  scene->getCurrentState());
63 }
64 
65 double countSamplesPerSecond(const ConstraintSamplerPtr& sampler, const moveit::core::RobotState& reference_state)
66 {
67  if (!sampler)
68  {
69  RCLCPP_ERROR(LOGGER, "No sampler specified for counting samples per second");
70  return 0.0;
71  }
72  moveit::core::RobotState ks(reference_state);
73  unsigned long int valid = 0;
74  unsigned long int total = 0;
75  rclcpp::Time end = rclcpp::Clock().now() + rclcpp::Duration::from_seconds(1);
76  do
77  {
78  static const unsigned int N = 10;
79  total += N;
80  for (unsigned int i = 0; i < N; ++i)
81  {
82  if (sampler->sample(ks, 1))
83  valid++;
84  }
85  } while (rclcpp::Clock().now() < end);
86  return (double)valid / (double)total;
87 }
88 
89 void visualizeDistribution(const ConstraintSamplerPtr& sampler, const moveit::core::RobotState& reference_state,
90  const std::string& link_name, unsigned int sample_count,
91  visualization_msgs::msg::MarkerArray& markers)
92 {
93  if (!sampler)
94  {
95  RCLCPP_ERROR(LOGGER, "No sampler specified for visualizing distribution of samples");
96  return;
97  }
98  const moveit::core::LinkModel* lm = reference_state.getLinkModel(link_name);
99  if (!lm)
100  return;
101  moveit::core::RobotState ks(reference_state);
102  std_msgs::msg::ColorRGBA color;
103  color.r = 1.0f;
104  color.g = 0.0f;
105  color.b = 0.0f;
106  color.a = 1.0f;
107  for (unsigned int i = 0; i < sample_count; ++i)
108  {
109  if (!sampler->sample(ks))
110  continue;
111  const Eigen::Vector3d& pos = ks.getGlobalLinkTransform(lm).translation();
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";
116  mk.id = i;
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;
124  mk.color = color;
125  mk.lifetime = rclcpp::Duration::from_seconds(30);
126  markers.markers.push_back(mk);
127  }
128 }
129 } // namespace constraint_samplers
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.
Definition: link_model.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:122
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...
Definition: robot_state.h:1339
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
Definition: fcl_compat.h:89
scene
Definition: pick.py:52