41 #include <moveit_msgs/GetConstraintAwarePositionIK.h>
42 #include <geometry_msgs/PoseStamped.h>
43 #include <moveit_msgs/msg/move_it_error_codes.hpp>
44 #include <moveit_msgs/msg/constraints.hpp>
45 #include <moveit_msgs/msg/robot_state.hpp>
93 const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
94 moveit_msgs::msg::GetConstraintAwarePositionIK::Response& response)
const;
103 return kinematic_model_;
107 EigenSTL::vector_Isometry3d transformPoses(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
109 const std::vector<geometry_msgs::PoseStamped>& poses,
110 const std::string& target_frame)
const;
112 bool convertServiceRequest(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
113 const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
117 geometry_msgs::Pose getTipFramePose(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
119 const std::string& link_name,
unsigned int sub_group_index)
const;
121 bool validityCallbackFn(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
124 moveit::core::JointStateGroup* joint_state_group,
125 const std::vector<double>& joint_group_variable_values)
const;
127 std::vector<std::string> sub_groups_names_;
129 moveit::core::RobotModelConstPtr kinematic_model_;
133 std::string group_name_;
135 bool has_sub_groups_;
137 unsigned int ik_attempts_;
const std::string & getGroupName() const
KinematicsConstraintAware(const moveit::core::RobotModelConstPtr &kinematic_model, const std::string &group_name)
Default constructor.
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
Solve the planning problem.
const moveit::core::RobotModelConstPtr & getRobotModel() const
Representation of a robot's state. This includes position, velocity, acceleration and effort.
std::shared_ptr< KinematicsConstraintAware > KinematicsConstraintAwarePtr
std::shared_ptr< const KinematicsConstraintAware > KinematicsConstraintAwareConstPtr
This namespace includes the central class for representing planning contexts.