moveit_opw_kinematics_plugin.h
Go to the documentation of this file.
1 #ifndef MOVEIT_OPW_KINEMATICS_PLUGIN_
2 #define MOVEIT_OPW_KINEMATICS_PLUGIN_
3 
4 // ROS
5 #include <ros/ros.h>
6 
7 // System
8 #include <memory>
9 
10 // ROS msgs
11 #include <geometry_msgs/PoseStamped.h>
12 #include <moveit_msgs/GetPositionFK.h>
13 #include <moveit_msgs/GetPositionIK.h>
14 #include <moveit_msgs/KinematicSolverInfo.h>
15 #include <moveit_msgs/MoveItErrorCodes.h>
16 
17 // MoveIt!
21 
22 // OPW kinematics
24 
26 {
33 {
34 public:
35  // struct for storing and sorting solutions
37  {
38  std::vector<double> value;
40 
41  bool operator<(const LimitObeyingSol& a) const
42  {
43  return dist_from_seed < a.dist_from_seed;
44  }
45  };
46 
51 
52  virtual bool
53  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
54  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
56 
57  virtual bool
58  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
59  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
61 
62  virtual bool
63  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
64  const std::vector<double>& consistency_limits, std::vector<double>& solution,
65  moveit_msgs::MoveItErrorCodes& error_code,
67 
68  virtual bool searchPositionIK(
69  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
70  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
72 
73  virtual bool
74  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
75  const std::vector<double>& consistency_limits, std::vector<double>& solution,
76  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
78 
79  virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
80  std::vector<geometry_msgs::Pose>& poses) const override;
81 
82  virtual bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
83  const std::string& base_frame, const std::vector<std::string>& tip_frames,
84  double search_discretization) override;
85 
89  const std::vector<std::string>& getJointNames() const override;
90 
94  const std::vector<std::string>& getLinkNames() const override;
95 
99  const std::vector<std::string>& getVariableNames() const;
100 
101  virtual bool
102  getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
103  std::vector<std::vector<double>>& solutions, KinematicsResult& result,
105 
106 protected:
107  virtual bool
108  searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
109  std::vector<double>& solution, const IKCallbackFn& solution_callback,
110  moveit_msgs::MoveItErrorCodes& error_code, const std::vector<double>& consistency_limits,
112 
113  virtual bool
114  searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
115  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
116  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
118 
119  virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices) override;
120 
121 private:
122  bool timedOut(const ros::WallTime& start_time, double duration) const;
123 
124  int getJointIndex(const std::string& name) const;
125 
126  bool isRedundantJoint(unsigned int index) const;
127 
128  bool setOPWParameters();
129 
130  static double distance(const std::vector<double>& a, const std::vector<double>& b);
131  static std::size_t closestJointPose(const std::vector<double>& target,
132  const std::vector<std::vector<double>>& candidates);
133  bool getAllIK(const Eigen::Isometry3d& pose, std::vector<std::vector<double>>& joint_poses) const;
134  bool getIK(const Eigen::Isometry3d& pose, const std::vector<double>& seed_state,
135  std::vector<double>& joint_pose) const;
136 
144  void expandIKSolutions(std::vector<std::vector<double>>& solutions) const;
145 
151  bool selfTest(const std::vector<double>& joint_angles);
152 
156  bool comparePoses(Eigen::Isometry3d& Ta, Eigen::Isometry3d& Tb);
157 
158  bool active_;
160  moveit_msgs::KinematicSolverInfo ik_group_info_;
162  unsigned int dimension_;
164  const robot_model::JointModelGroup* joint_model_group_;
165 
166  robot_state::RobotStatePtr robot_state_;
167 
169 
171 };
172 } // namespace moveit_opw_kinematics_plugin
173 
174 #endif
static std::size_t closestJointPose(const std::vector< double > &target, const std::vector< std::vector< double >> &candidates)
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool getIK(const Eigen::Isometry3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const
bool comparePoses(Eigen::Isometry3d &Ta, Eigen::Isometry3d &Tb)
check if two poses are the same within an absolute tolerance of 1e-6
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
unsigned int index
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
options
static double distance(const std::vector< double > &a, const std::vector< double > &b)
bool timedOut(const ros::WallTime &start_time, double duration) const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
bool getAllIK(const Eigen::Isometry3d &pose, std::vector< std::vector< double >> &joint_poses) const
bool selfTest(const std::vector< double > &joint_angles)
check forward and inverse kinematics consistency
void expandIKSolutions(std::vector< std::vector< double >> &solutions) const
append IK solutions by adding +-2pi
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
virtual bool initialize(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override


moveit_opw_kinematics_plugin
Author(s): Jeroen De Maeyer, Simon Schmeisser (isys vision)
autogenerated on Mon Feb 28 2022 22:50:11