srv_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, JSK, The University of Tokyo.
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 JSK, The University of Tokyo 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: Dave Coleman, Masaki Murooka
36  Desc: Connects MoveIt to any inverse kinematics solver via a ROS service call
37  Supports planning groups with multiple tip frames
38  \todo: better support for mimic joints
39  \todo: better support for redundant joints
40 */
41 
42 #pragma once
43 
44 // ROS
45 #include <ros/ros.h>
46 
47 // System
48 #include <memory>
49 
50 // ROS msgs
51 #include <geometry_msgs/Pose.h>
52 #include <moveit_msgs/KinematicSolverInfo.h>
53 #include <moveit_msgs/MoveItErrorCodes.h>
54 
55 // MoveIt
58 
60 {
66 {
67 public:
72 
73  bool
74  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
75  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
77 
78  bool searchPositionIK(
79  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
80  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
82 
83  bool searchPositionIK(
84  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
85  const std::vector<double>& consistency_limits, std::vector<double>& solution,
86  moveit_msgs::MoveItErrorCodes& error_code,
88 
89  bool searchPositionIK(
90  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
91  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
93 
94  bool searchPositionIK(
95  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
96  const std::vector<double>& consistency_limits, std::vector<double>& solution,
97  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
99 
100  bool searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
101  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
102  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
104  const moveit::core::RobotState* context_state = nullptr) const override;
105 
106  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
107  std::vector<geometry_msgs::Pose>& poses) const override;
108 
109  bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
110  const std::string& base_name, const std::vector<std::string>& tip_frames,
111  double search_discretization) override;
112 
116  const std::vector<std::string>& getJointNames() const override;
117 
121  const std::vector<std::string>& getLinkNames() const override;
122 
126  const std::vector<std::string>& getVariableNames() const;
127 
128 protected:
129  bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices) override;
130 
131 private:
132  bool timedOut(const ros::WallTime& start_time, double duration) const;
133 
134  int getJointIndex(const std::string& name) const;
135 
136  bool isRedundantJoint(unsigned int index) const;
137 
138  bool active_;
140  moveit_msgs::KinematicSolverInfo ik_group_info_;
142  unsigned int dimension_;
145 
146  moveit::core::RobotStatePtr robot_state_;
147 
149 
150  std::shared_ptr<ros::ServiceClient> ik_service_client_;
151 };
152 } // namespace srv_kinematics_plugin
srv_kinematics_plugin::SrvKinematicsPlugin::getLinkNames
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
Definition: srv_kinematics_plugin.cpp:423
srv_kinematics_plugin::SrvKinematicsPlugin::getJointIndex
int getJointIndex(const std::string &name) const
Definition: srv_kinematics_plugin.cpp:187
duration
std::chrono::system_clock::duration duration
srv_kinematics_plugin::SrvKinematicsPlugin::robot_state_
moveit::core::RobotStatePtr robot_state_
Definition: srv_kinematics_plugin.h:210
ros.h
moveit::core::RobotModel
moveit::core::RobotState
robot_state.h
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
srv_kinematics_plugin::SrvKinematicsPlugin::searchPositionIK
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
Definition: srv_kinematics_plugin.cpp:212
srv_kinematics_plugin
Definition: srv_kinematics_plugin.h:59
srv_kinematics_plugin::SrvKinematicsPlugin::num_possible_redundant_joints_
int num_possible_redundant_joints_
Definition: srv_kinematics_plugin.h:212
srv_kinematics_plugin::SrvKinematicsPlugin::initialize
bool initialize(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override
Definition: srv_kinematics_plugin.cpp:87
srv_kinematics_plugin::SrvKinematicsPlugin::timedOut
bool timedOut(const ros::WallTime &start_time, double duration) const
Definition: srv_kinematics_plugin.cpp:197
kinematics::KinematicsBase
srv_kinematics_plugin::SrvKinematicsPlugin::getPositionIK
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
Definition: srv_kinematics_plugin.cpp:202
ros::WallTime
srv_kinematics_plugin::SrvKinematicsPlugin::getVariableNames
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
Definition: srv_kinematics_plugin.cpp:428
srv_kinematics_plugin::SrvKinematicsPlugin::ik_service_client_
std::shared_ptr< ros::ServiceClient > ik_service_client_
Definition: srv_kinematics_plugin.h:214
srv_kinematics_plugin::SrvKinematicsPlugin
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
Definition: srv_kinematics_plugin.h:97
kinematics::KinematicsQueryOptions
srv_kinematics_plugin::SrvKinematicsPlugin::setRedundantJoints
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
Definition: srv_kinematics_plugin.cpp:163
kinematics_base.h
srv_kinematics_plugin::SrvKinematicsPlugin::ik_group_info_
moveit_msgs::KinematicSolverInfo ik_group_info_
Definition: srv_kinematics_plugin.h:204
moveit::core::JointModelGroup
srv_kinematics_plugin::SrvKinematicsPlugin::isRedundantJoint
bool isRedundantJoint(unsigned int index) const
Definition: srv_kinematics_plugin.cpp:179
srv_kinematics_plugin::SrvKinematicsPlugin::getPositionFK
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
Definition: srv_kinematics_plugin.cpp:397
srv_kinematics_plugin::SrvKinematicsPlugin::SrvKinematicsPlugin
SrvKinematicsPlugin()
Default constructor.
Definition: srv_kinematics_plugin.cpp:83
srv_kinematics_plugin::SrvKinematicsPlugin::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: srv_kinematics_plugin.h:208
srv_kinematics_plugin::SrvKinematicsPlugin::getJointNames
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
Definition: srv_kinematics_plugin.cpp:418
srv_kinematics_plugin::SrvKinematicsPlugin::active_
bool active_
Definition: srv_kinematics_plugin.h:202
srv_kinematics_plugin::SrvKinematicsPlugin::dimension_
unsigned int dimension_
Definition: srv_kinematics_plugin.h:206


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:15