|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#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 |
Definition at line 66 of file kinematics_constraint_aware.h.
| kinematics_constraint_aware::KinematicsConstraintAware::KinematicsConstraintAware | ( | const moveit::core::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 48 of file kinematics_constraint_aware.cpp.

|
inline |
Definition at line 96 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 103 of file kinematics_constraint_aware.cpp.


| 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.
| 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 251 of file kinematics_constraint_aware.cpp.

|
inline |
Definition at line 101 of file kinematics_constraint_aware.h.