bio_ik
MoveIt kinematics_base plugin based on particle optimization & GA
problem.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016-2017, Philipp Sebastian Ruppel
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 the copyright holder 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 #pragma once
36 
37 #include "utils.h"
38 #include <vector>
39 
40 #include <bio_ik/robot_info.h>
41 
42 #include <geometric_shapes/shapes.h>
43 
44 #include <moveit/collision_detection/collision_common.h>
45 #include <moveit/collision_detection_fcl/collision_common.h>
46 
47 #include <bio_ik/goal.h>
48 
49 namespace bio_ik
50 {
51 
52 class Problem
53 {
54 private:
55  bool ros_params_initrd;
56  std::vector<int> joint_usage;
57  std::vector<ssize_t> link_tip_indices;
58  std::vector<double> minimal_displacement_factors;
59  std::vector<double> joint_transmission_goal_temp, joint_transmission_goal_temp2;
60  moveit::core::RobotModelConstPtr robot_model;
61  const moveit::core::JointModelGroup* joint_model_group;
62  IKParams params;
63  RobotInfo modelInfo;
64  double dpos, drot, dtwist;
65 #if (MOVEIT_FCL_VERSION < FCL_VERSION_CHECK(0, 6, 0))
66  struct CollisionShape
67  {
68  std::vector<Vector3> vertices;
69  std::vector<fcl::Vec3f> points;
70  std::vector<int> polygons;
71  std::vector<fcl::Vec3f> plane_normals;
72  std::vector<double> plane_dis;
73  collision_detection::FCLGeometryConstPtr geometry;
74  Frame frame;
75  std::vector<std::vector<size_t>> edges;
76  };
77  struct CollisionLink
78  {
79  bool initialized;
80  std::vector<std::shared_ptr<CollisionShape>> shapes;
81  CollisionLink()
82  : initialized(false)
83  {
84  }
85  };
86  std::vector<CollisionLink> collision_links;
87 #endif
88  size_t addTipLink(const moveit::core::LinkModel* link_model);
89 
90 public:
91  /*enum class GoalType;
92  struct BalanceGoalInfo
93  {
94  ssize_t tip_index;
95  double mass;
96  Vector3 center;
97  };
98  struct GoalInfo
99  {
100  const Goal* goal;
101  GoalType goal_type;
102  size_t tip_index;
103  double weight;
104  double weight_sq;
105  double rotation_scale;
106  double rotation_scale_sq;
107  Frame frame;
108  tf2::Vector3 target;
109  tf2::Vector3 direction;
110  tf2::Vector3 axis;
111  double distance;
112  ssize_t active_variable_index;
113  double variable_position;
114  std::vector<ssize_t> variable_indices;
115  mutable size_t last_collision_vertex;
116  std::vector<BalanceGoalInfo> balance_goal_infos;
117  };*/
118  enum class GoalType;
119  // std::vector<const Frame*> temp_frames;
120  // std::vector<double> temp_variables;
121  struct GoalInfo
122  {
123  const Goal* goal;
124  double weight_sq;
125  double weight;
126  GoalType goal_type;
127  size_t tip_index;
128  Frame frame;
129  GoalContext goal_context;
130  };
131  double timeout;
132  std::vector<double> initial_guess;
133  std::vector<size_t> active_variables;
134  std::vector<size_t> tip_link_indices;
135  std::vector<GoalInfo> goals;
136  std::vector<GoalInfo> secondary_goals;
137  Problem();
138  void initialize(moveit::core::RobotModelConstPtr robot_model, const moveit::core::JointModelGroup* joint_model_group, const IKParams& params, const std::vector<const Goal*>& goals2, const BioIKKinematicsQueryOptions* options);
139  void initialize2();
140  double computeGoalFitness(GoalInfo& goal, const Frame* tip_frames, const double* active_variable_positions);
141  double computeGoalFitness(std::vector<GoalInfo>& goals, const Frame* tip_frames, const double* active_variable_positions);
142  bool checkSolutionActiveVariables(const std::vector<Frame>& tip_frames, const double* active_variable_positions);
143 };
144 }