|
| 1 | +/********************************************************************* |
| 2 | + * Software License Agreement (BSD License) |
| 3 | + * |
| 4 | + * Copyright (c) 2020, PickNik 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 PickNik Inc 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 | +/* Authors: Henning Kayser */ |
| 36 | + |
| 37 | +#include <moveit/task_constructor/stages/generate_random_pose.h> |
| 38 | +#include <moveit/task_constructor/storage.h> |
| 39 | +#include <moveit/task_constructor/marker_tools.h> |
| 40 | +#include <moveit/planning_scene/planning_scene.h> |
| 41 | +#include <rviz_marker_tools/marker_creation.h> |
| 42 | + |
| 43 | +#include <Eigen/Geometry> |
| 44 | +#include <tf2_eigen/tf2_eigen.h> |
| 45 | + |
| 46 | +#include <chrono> |
| 47 | + |
| 48 | +namespace { |
| 49 | +// TODO(henningkayser): support user-defined random number engines |
| 50 | +std::random_device RANDOM_DEVICE; |
| 51 | +std::mt19937 ENGINE(RANDOM_DEVICE()); |
| 52 | +} // namespace |
| 53 | + |
| 54 | +namespace moveit { |
| 55 | +namespace task_constructor { |
| 56 | +namespace stages { |
| 57 | + |
| 58 | +GenerateRandomPose::GenerateRandomPose(const std::string& name) : GeneratePose(name) { |
| 59 | + auto& p = properties(); |
| 60 | + p.declare<size_t>("max_solutions", 20, "maximum number of spawned solutions"); |
| 61 | + p.property("pose").setDescription("seed pose"); |
| 62 | + p.property("timeout").setDefaultValue(1.0 /* seconds */); |
| 63 | +} |
| 64 | + |
| 65 | +template <> |
| 66 | +GenerateRandomPose::PoseDimensionSampler |
| 67 | +GenerateRandomPose::getPoseDimensionSampler<std::normal_distribution>(double stddev) { |
| 68 | + return [stddev](double mean) { |
| 69 | + static std::normal_distribution<double> dist(mean, stddev); |
| 70 | + return dist(ENGINE); |
| 71 | + }; |
| 72 | +} |
| 73 | + |
| 74 | +template <> |
| 75 | +GenerateRandomPose::PoseDimensionSampler |
| 76 | +GenerateRandomPose::getPoseDimensionSampler<std::uniform_real_distribution>(double range) { |
| 77 | + return [range](double mean) { |
| 78 | + static std::uniform_real_distribution<double> dist(mean - 0.5 * range, mean + 0.5 * range); |
| 79 | + return dist(ENGINE); |
| 80 | + }; |
| 81 | +} |
| 82 | + |
| 83 | +bool GenerateRandomPose::canCompute() const { |
| 84 | + return GeneratePose::canCompute() && !pose_dimension_samplers_.empty(); |
| 85 | +} |
| 86 | + |
| 87 | +void GenerateRandomPose::compute() { |
| 88 | + if (upstream_solutions_.empty()) |
| 89 | + return; |
| 90 | + |
| 91 | + const SolutionBase& s = *upstream_solutions_.pop(); |
| 92 | + planning_scene::PlanningScenePtr scene = s.end()->scene()->diff(); |
| 93 | + geometry_msgs::PoseStamped seed_pose = properties().get<geometry_msgs::PoseStamped>("pose"); |
| 94 | + if (seed_pose.header.frame_id.empty()) |
| 95 | + seed_pose.header.frame_id = scene->getPlanningFrame(); |
| 96 | + else if (!scene->knowsFrameTransform(seed_pose.header.frame_id)) { |
| 97 | + ROS_WARN_NAMED("GenerateRandomPose", "Unknown frame: '%s'", seed_pose.header.frame_id.c_str()); |
| 98 | + return; |
| 99 | + } |
| 100 | + |
| 101 | + const auto& spawn_target_pose = [&](const geometry_msgs::PoseStamped& target_pose) { |
| 102 | + InterfaceState state(scene); |
| 103 | + forwardProperties(*s.end(), state); // forward registered properties from received solution |
| 104 | + state.properties().set("target_pose", target_pose); |
| 105 | + |
| 106 | + SubTrajectory trajectory; |
| 107 | + trajectory.setCost(0.0); |
| 108 | + |
| 109 | + rviz_marker_tools::appendFrame(trajectory.markers(), target_pose, 0.1, "pose frame"); |
| 110 | + |
| 111 | + spawn(std::move(state), std::move(trajectory)); |
| 112 | + }; |
| 113 | + |
| 114 | + spawn_target_pose(seed_pose); |
| 115 | + |
| 116 | + if (pose_dimension_samplers_.empty()) |
| 117 | + return; |
| 118 | + |
| 119 | + geometry_msgs::PoseStamped sample_pose = seed_pose; |
| 120 | + Eigen::Isometry3d seed, sample; |
| 121 | + tf2::fromMsg(seed_pose.pose, seed); |
| 122 | + double elapsed_time = 0.0; |
| 123 | + const auto start_time = std::chrono::steady_clock::now(); |
| 124 | + size_t spawned_solutions = 0; |
| 125 | + const size_t max_solutions = properties().get<size_t>("max_solutions"); |
| 126 | + |
| 127 | + while (elapsed_time < timeout() && ++spawned_solutions < max_solutions) { |
| 128 | + // Randomize pose using specified dimension samplers applied |
| 129 | + // in the order in which they have been specified |
| 130 | + sample = seed; |
| 131 | + for (const auto& pose_dim_sampler : pose_dimension_samplers_) { |
| 132 | + switch (pose_dim_sampler.first) { |
| 133 | + case X: |
| 134 | + sample.translate(Eigen::Vector3d(pose_dim_sampler.second(0), 0, 0)); |
| 135 | + break; |
| 136 | + case Y: |
| 137 | + sample.translate(Eigen::Vector3d(0, pose_dim_sampler.second(0), 0)); |
| 138 | + break; |
| 139 | + case Z: |
| 140 | + sample.translate(Eigen::Vector3d(0, 0, pose_dim_sampler.second(0))); |
| 141 | + break; |
| 142 | + case ROLL: |
| 143 | + sample.rotate(Eigen::AngleAxisd(pose_dim_sampler.second(0.0), Eigen::Vector3d::UnitX())); |
| 144 | + break; |
| 145 | + case PITCH: |
| 146 | + sample.rotate(Eigen::AngleAxisd(pose_dim_sampler.second(0.0), Eigen::Vector3d::UnitY())); |
| 147 | + break; |
| 148 | + case YAW: |
| 149 | + sample.rotate(Eigen::AngleAxisd(pose_dim_sampler.second(0.0), Eigen::Vector3d::UnitZ())); |
| 150 | + } |
| 151 | + } |
| 152 | + sample_pose.pose = tf2::toMsg(sample); |
| 153 | + spawn_target_pose(sample_pose); |
| 154 | + |
| 155 | + elapsed_time = std::chrono::duration<double>(std::chrono::steady_clock::now() - start_time).count(); |
| 156 | + } |
| 157 | +} |
| 158 | +} // namespace stages |
| 159 | +} // namespace task_constructor |
| 160 | +} // namespace moveit |
0 commit comments