#include <kinematics_constraint_aware.h>
Public Member Functions | |
| const std::string & | getGroupName () const |
| bool | getIK (const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const |
| Solve the planning problem. | |
| bool | getIK (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetConstraintAwarePositionIK::Request &request, moveit_msgs::GetConstraintAwarePositionIK::Response &response) const |
| Solve the planning problem. | |
| const robot_model::RobotModelConstPtr & | getRobotModel () const |
| KinematicsConstraintAware (const robot_model::RobotModelConstPtr &kinematic_model, const std::string &group_name) | |
| Default constructor. | |
Private Member Functions | |
| bool | convertServiceRequest (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetConstraintAwarePositionIK::Request &request, kinematics_constraint_aware::KinematicsRequest &kinematics_request, kinematics_constraint_aware::KinematicsResponse &kinematics_response) const |
| geometry_msgs::Pose | getTipFramePose (const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_state::RobotState &kinematic_state, const geometry_msgs::Pose &pose, const std::string &link_name, unsigned int sub_group_index) const |
| EigenSTL::vector_Affine3d | transformPoses (const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_state::RobotState &kinematic_state, const std::vector< geometry_msgs::PoseStamped > &poses, const std::string &target_frame) const |
| bool | validityCallbackFn (const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response, robot_state::JointStateGroup *joint_state_group, const std::vector< double > &joint_group_variable_values) const |
Private Attributes | |
| std::string | group_name_ |
| bool | has_sub_groups_ |
| unsigned int | ik_attempts_ |
| const robot_model::JointModelGroup * | joint_model_group_ |
| robot_model::RobotModelConstPtr | kinematic_model_ |
| std::vector< std::string > | sub_groups_names_ |
Definition at line 71 of file kinematics_constraint_aware.h.
| kinematics_constraint_aware::KinematicsConstraintAware::KinematicsConstraintAware | ( | const robot_model::RobotModelConstPtr & | kinematic_model, |
| const std::string & | group_name | ||
| ) |
Default constructor.
| kinematic_model | An instance of a kinematic model |
| group_name | The name of the group to configure this solver for |
Definition at line 47 of file kinematics_constraint_aware.cpp.
| bool kinematics_constraint_aware::KinematicsConstraintAware::convertServiceRequest | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
| const moveit_msgs::GetConstraintAwarePositionIK::Request & | request, | ||
| kinematics_constraint_aware::KinematicsRequest & | kinematics_request, | ||
| kinematics_constraint_aware::KinematicsResponse & | kinematics_response | ||
| ) | const [private] |
Definition at line 277 of file kinematics_constraint_aware.cpp.
| const std::string& kinematics_constraint_aware::KinematicsConstraintAware::getGroupName | ( | ) | const [inline] |
Definition at line 101 of file kinematics_constraint_aware.h.
| bool kinematics_constraint_aware::KinematicsConstraintAware::getIK | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
| const kinematics_constraint_aware::KinematicsRequest & | request, | ||
| kinematics_constraint_aware::KinematicsResponse & | response | ||
| ) | const |
Solve the planning problem.
| planning_scene | A const reference to the planning scene |
| request | A const reference to the kinematics request |
| response | The solution (if it exists) |
Definition at line 100 of file kinematics_constraint_aware.cpp.
| bool kinematics_constraint_aware::KinematicsConstraintAware::getIK | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
| const moveit_msgs::GetConstraintAwarePositionIK::Request & | request, | ||
| moveit_msgs::GetConstraintAwarePositionIK::Response & | response | ||
| ) | const |
Solve the planning problem.
| planning_scene | A const reference to the planning scene |
| request | A const reference to the kinematics request |
| response | The solution (if it exists) |
Definition at line 246 of file kinematics_constraint_aware.cpp.
| const robot_model::RobotModelConstPtr& kinematics_constraint_aware::KinematicsConstraintAware::getRobotModel | ( | ) | const [inline] |
Definition at line 106 of file kinematics_constraint_aware.h.
| geometry_msgs::Pose kinematics_constraint_aware::KinematicsConstraintAware::getTipFramePose | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
| const robot_state::RobotState & | kinematic_state, | ||
| const geometry_msgs::Pose & | pose, | ||
| const std::string & | link_name, | ||
| unsigned int | sub_group_index | ||
| ) | const [private] |
Definition at line 353 of file kinematics_constraint_aware.cpp.
| EigenSTL::vector_Affine3d kinematics_constraint_aware::KinematicsConstraintAware::transformPoses | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
| const robot_state::RobotState & | kinematic_state, | ||
| const std::vector< geometry_msgs::PoseStamped > & | poses, | ||
| const std::string & | target_frame | ||
| ) | const [private] |
Definition at line 331 of file kinematics_constraint_aware.cpp.
| bool kinematics_constraint_aware::KinematicsConstraintAware::validityCallbackFn | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
| const kinematics_constraint_aware::KinematicsRequest & | request, | ||
| kinematics_constraint_aware::KinematicsResponse & | response, | ||
| robot_state::JointStateGroup * | joint_state_group, | ||
| const std::vector< double > & | joint_group_variable_values | ||
| ) | const [private] |
Definition at line 195 of file kinematics_constraint_aware.cpp.
std::string kinematics_constraint_aware::KinematicsConstraintAware::group_name_ [private] |
Definition at line 138 of file kinematics_constraint_aware.h.
Definition at line 140 of file kinematics_constraint_aware.h.
unsigned int kinematics_constraint_aware::KinematicsConstraintAware::ik_attempts_ [private] |
Definition at line 142 of file kinematics_constraint_aware.h.
const robot_model::JointModelGroup* kinematics_constraint_aware::KinematicsConstraintAware::joint_model_group_ [private] |
Definition at line 136 of file kinematics_constraint_aware.h.
robot_model::RobotModelConstPtr kinematics_constraint_aware::KinematicsConstraintAware::kinematic_model_ [private] |
Definition at line 134 of file kinematics_constraint_aware.h.
std::vector<std::string> kinematics_constraint_aware::KinematicsConstraintAware::sub_groups_names_ [private] |
Definition at line 132 of file kinematics_constraint_aware.h.