moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
kinematics_constraint_aware::KinematicsConstraintAware Class Reference

#include <kinematics_constraint_aware.h>

Public Member Functions

 KinematicsConstraintAware (const moveit::core::RobotModelConstPtr &kinematic_model, const std::string &group_name)
 Default constructor. More...
 
bool getIK (const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
 Solve the planning problem. More...
 
bool getIK (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::msg::GetConstraintAwarePositionIK::Request &request, moveit_msgs::msg::GetConstraintAwarePositionIK::Response &response) const
 Solve the planning problem. More...
 
const std::string & getGroupName () const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 

Detailed Description

Definition at line 66 of file kinematics_constraint_aware.h.

Constructor & Destructor Documentation

◆ KinematicsConstraintAware()

kinematics_constraint_aware::KinematicsConstraintAware::KinematicsConstraintAware ( const moveit::core::RobotModelConstPtr &  kinematic_model,
const std::string &  group_name 
)

Default constructor.

Parameters
kinematic_modelAn instance of a kinematic model
group_nameThe 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.

Here is the call graph for this function:

Member Function Documentation

◆ getGroupName()

const std::string& kinematics_constraint_aware::KinematicsConstraintAware::getGroupName ( ) const
inline

Definition at line 96 of file kinematics_constraint_aware.h.

◆ getIK() [1/2]

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.

Parameters
planning_sceneA const reference to the planning scene
requestA const reference to the kinematics request
responseThe solution (if it exists)
Returns
False if group_name is invalid or ik fails

Definition at line 103 of file kinematics_constraint_aware.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getIK() [2/2]

bool kinematics_constraint_aware::KinematicsConstraintAware::getIK ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::msg::GetConstraintAwarePositionIK::Request &  request,
moveit_msgs::msg::GetConstraintAwarePositionIK::Response &  response 
) const

Solve the planning problem.

Parameters
planning_sceneA const reference to the planning scene
requestA const reference to the kinematics request
responseThe solution (if it exists)
Returns
False if group_name is invalid or ik fails

Definition at line 251 of file kinematics_constraint_aware.cpp.

Here is the call graph for this function:

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& kinematics_constraint_aware::KinematicsConstraintAware::getRobotModel ( ) const
inline

Definition at line 101 of file kinematics_constraint_aware.h.


The documentation for this class was generated from the following files: