#include <kinematics_constraint_aware.h>
|
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 |
|
kinematics_constraint_aware::KinematicsConstraintAware::KinematicsConstraintAware |
( |
const robot_model::RobotModelConstPtr & |
kinematic_model, |
|
|
const std::string & |
group_name |
|
) |
| |
Default constructor.
- Parameters
-
kinematic_model | An instance of a kinematic model |
group_name | The name of the group to configure this solver for |
- Returns
- False if any error occurs
Definition at line 48 of file kinematics_constraint_aware.cpp.
const std::string& kinematics_constraint_aware::KinematicsConstraintAware::getGroupName |
( |
| ) |
const |
|
inline |
Solve the planning problem.
- Parameters
-
planning_scene | A const reference to the planning scene |
request | A const reference to the kinematics request |
response | The solution (if it exists) |
- Returns
- False if group_name is invalid or ik fails
Definition at line 103 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.
- Parameters
-
planning_scene | A const reference to the planning scene |
request | A const reference to the kinematics request |
response | The solution (if it exists) |
- Returns
- False if group_name is invalid or ik fails
Definition at line 249 of file kinematics_constraint_aware.cpp.
const robot_model::RobotModelConstPtr& kinematics_constraint_aware::KinematicsConstraintAware::getRobotModel |
( |
| ) |
const |
|
inline |
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 |
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 |
std::string kinematics_constraint_aware::KinematicsConstraintAware::group_name_ |
|
private |
bool kinematics_constraint_aware::KinematicsConstraintAware::has_sub_groups_ |
|
private |
unsigned int kinematics_constraint_aware::KinematicsConstraintAware::ik_attempts_ |
|
private |
const robot_model::JointModelGroup* kinematics_constraint_aware::KinematicsConstraintAware::joint_model_group_ |
|
private |
robot_model::RobotModelConstPtr kinematics_constraint_aware::KinematicsConstraintAware::kinematic_model_ |
|
private |
std::vector<std::string> kinematics_constraint_aware::KinematicsConstraintAware::sub_groups_names_ |
|
private |
The documentation for this class was generated from the following files: