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 #include <moveit/utils/logger.hpp>
45 
46 namespace constraint_samplers
47 {
48 namespace
49 {
50 rclcpp::Logger getLogger()
51 {
52  return moveit::getLogger("constraint_sampler_tools");
53 }
54 } // namespace
55 
56 void visualizeDistribution(const moveit_msgs::msg::Constraints& constr,
57  const planning_scene::PlanningSceneConstPtr& scene, const std::string& group,
58  const std::string& link_name, unsigned int sample_count,
59  visualization_msgs::msg::MarkerArray& markers)
60 {
61  visualizeDistribution(ConstraintSamplerManager::selectDefaultSampler(scene, group, constr), scene->getCurrentState(),
62  link_name, sample_count, markers);
63 }
64 
65 double countSamplesPerSecond(const moveit_msgs::msg::Constraints& constr,
66  const planning_scene::PlanningSceneConstPtr& scene, const std::string& group)
67 {
69  scene->getCurrentState());
70 }
71 
72 double countSamplesPerSecond(const ConstraintSamplerPtr& sampler, const moveit::core::RobotState& reference_state)
73 {
74  if (!sampler)
75  {
76  RCLCPP_ERROR(getLogger(), "No sampler specified for counting samples per second");
77  return 0.0;
78  }
79  moveit::core::RobotState ks(reference_state);
80  unsigned long int valid = 0;
81  unsigned long int total = 0;
82  rclcpp::Time end = rclcpp::Clock().now() + rclcpp::Duration::from_seconds(1);
83  do
84  {
85  static const unsigned int N = 10;
86  total += N;
87  for (unsigned int i = 0; i < N; ++i)
88  {
89  if (sampler->sample(ks, 1))
90  valid++;
91  }
92  } while (rclcpp::Clock().now() < end);
93  return static_cast<double>(valid) / static_cast<double>(total);
94 }
95 
96 void visualizeDistribution(const ConstraintSamplerPtr& sampler, const moveit::core::RobotState& reference_state,
97  const std::string& link_name, unsigned int sample_count,
98  visualization_msgs::msg::MarkerArray& markers)
99 {
100  if (!sampler)
101  {
102  RCLCPP_ERROR(getLogger(), "No sampler specified for visualizing distribution of samples");
103  return;
104  }
105  const moveit::core::LinkModel* lm = reference_state.getLinkModel(link_name);
106  if (!lm)
107  return;
108  moveit::core::RobotState ks(reference_state);
109  std_msgs::msg::ColorRGBA color;
110  color.r = 1.0f;
111  color.g = 0.0f;
112  color.b = 0.0f;
113  color.a = 1.0f;
114  for (unsigned int i = 0; i < sample_count; ++i)
115  {
116  if (!sampler->sample(ks))
117  continue;
118  const Eigen::Vector3d& pos = ks.getGlobalLinkTransform(lm).translation();
119  visualization_msgs::msg::Marker mk;
120  mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
121  mk.header.frame_id = sampler->getJointModelGroup()->getParentModel().getModelFrame();
122  mk.ns = "constraint_samples";
123  mk.id = i;
124  mk.type = visualization_msgs::msg::Marker::SPHERE;
125  mk.action = visualization_msgs::msg::Marker::ADD;
126  mk.pose.position.x = pos.x();
127  mk.pose.position.y = pos.y();
128  mk.pose.position.z = pos.z();
129  mk.pose.orientation.w = 1.0;
130  mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
131  mk.color = color;
132  mk.lifetime = rclcpp::Duration::from_seconds(30);
133  markers.markers.push_back(mk);
134  }
135 }
136 } // 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:1246
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79