manipulation_plan.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Sachin Chitta */
36 
37 #pragma once
38 
43 #include <moveit_msgs/GripperTranslation.h>
44 #include <moveit_msgs/RobotState.h>
45 #include <moveit_msgs/RobotTrajectory.h>
46 #include <moveit_msgs/MoveItErrorCodes.h>
47 #include <moveit_msgs/Constraints.h>
48 #include <string>
49 #include <vector>
50 
51 namespace pick_place
52 {
53 MOVEIT_STRUCT_FORWARD(ManipulationPlanSharedData);
54 
55 struct ManipulationPlanSharedData
56 {
58  : planning_group_(nullptr)
59  , end_effector_group_(nullptr)
60  , ik_link_(nullptr)
63  {
64  }
65 
69 
70  unsigned int max_goal_sampling_attempts_;
71 
72  std::string planner_id_;
73 
75 
76  moveit_msgs::Constraints path_constraints_;
77 
78  moveit_msgs::AttachedCollisionObject diff_attached_object_;
79 
81 };
82 
83 MOVEIT_STRUCT_FORWARD(ManipulationPlan);
84 
85 struct ManipulationPlan
86 {
87  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
88 
89  ManipulationPlan(const ManipulationPlanSharedDataConstPtr& shared_data)
90  : shared_data_(shared_data), processing_stage_(0)
91  {
92  }
93 
95  void clear()
96  {
97  goal_sampler_.reset();
98  trajectories_.clear();
99  approach_state_.reset();
101  processing_stage_ = 0;
102  }
103 
104  // Shared data between manipulation plans (set at initialization)
105  ManipulationPlanSharedDataConstPtr shared_data_;
106 
107  // the approach motion towards the goal
108  moveit_msgs::GripperTranslation approach_;
109 
110  // the retreat motion away from the goal
111  moveit_msgs::GripperTranslation retreat_;
112 
113  // the kinematic configuration of the end effector when approaching the goal (an open gripper)
114  trajectory_msgs::JointTrajectory approach_posture_;
115 
116  // the kinematic configuration of the end effector when retreating from the goal (a closed gripper)
117  trajectory_msgs::JointTrajectory retreat_posture_;
118 
119  // -------------- computed data --------------------------
120  geometry_msgs::PoseStamped goal_pose_;
121  Eigen::Isometry3d transformed_goal_pose_;
122 
123  moveit_msgs::Constraints goal_constraints_;
124 
125  // Allows for the sampling of a kineamtic state for a particular group of a robot
126  constraint_samplers::ConstraintSamplerPtr goal_sampler_;
127 
128  std::vector<moveit::core::RobotStatePtr> possible_goal_states_;
129 
130  moveit::core::RobotStatePtr approach_state_;
131 
132  // The sequence of trajectories produced for execution
133  std::vector<plan_execution::ExecutableTrajectory> trajectories_;
134 
135  // An error code reflecting what went wrong (if anything)
136  moveit_msgs::MoveItErrorCodes error_code_;
137 
138  // The processing stage that was last working on this plan, or was about to work on this plan
139  std::size_t processing_stage_;
140 
141  // An id for this plan; this is usually the index of the Grasp / PlaceLocation in the input request
142  std::size_t id_;
143 };
144 } // namespace pick_place
moveit::core::LinkModel
pick_place::ManipulationPlan::id_
std::size_t id_
Definition: manipulation_plan.h:174
pick_place
Definition: approach_and_translate_stage.h:43
pick_place::ManipulationPlan::approach_state_
moveit::core::RobotStatePtr approach_state_
Definition: manipulation_plan.h:162
plan_representation.h
pick_place::MOVEIT_STRUCT_FORWARD
MOVEIT_STRUCT_FORWARD(ManipulationPlanSharedData)
pick_place::ManipulationPlanSharedData::path_constraints_
moveit_msgs::Constraints path_constraints_
Definition: manipulation_plan.h:108
robot_state.h
pick_place::ManipulationPlanSharedData::planning_group_
const moveit::core::JointModelGroup * planning_group_
Definition: manipulation_plan.h:98
pick_place::ManipulationPlan::goal_sampler_
constraint_samplers::ConstraintSamplerPtr goal_sampler_
Definition: manipulation_plan.h:158
pick_place::ManipulationPlanSharedData::minimize_object_distance_
bool minimize_object_distance_
Definition: manipulation_plan.h:106
pick_place::ManipulationPlan::trajectories_
std::vector< plan_execution::ExecutableTrajectory > trajectories_
Definition: manipulation_plan.h:165
pick_place::ManipulationPlan::goal_pose_
geometry_msgs::PoseStamped goal_pose_
Definition: manipulation_plan.h:152
pick_place::ManipulationPlan::processing_stage_
std::size_t processing_stage_
Definition: manipulation_plan.h:171
pick_place::ManipulationPlan::ManipulationPlan
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ManipulationPlan(const ManipulationPlanSharedDataConstPtr &shared_data)
Definition: manipulation_plan.h:121
pick_place::ManipulationPlanSharedData::planner_id_
std::string planner_id_
Definition: manipulation_plan.h:104
pick_place::ManipulationPlan::possible_goal_states_
std::vector< moveit::core::RobotStatePtr > possible_goal_states_
Definition: manipulation_plan.h:160
pick_place::ManipulationPlanSharedData::diff_attached_object_
moveit_msgs::AttachedCollisionObject diff_attached_object_
Definition: manipulation_plan.h:110
pick_place::ManipulationPlan::approach_posture_
trajectory_msgs::JointTrajectory approach_posture_
Definition: manipulation_plan.h:146
pick_place::ManipulationPlanSharedData::ManipulationPlanSharedData
ManipulationPlanSharedData()
Definition: manipulation_plan.h:89
ros::WallTime
pick_place::ManipulationPlanSharedData::ik_link_
const moveit::core::LinkModel * ik_link_
Definition: manipulation_plan.h:100
pick_place::ManipulationPlan::shared_data_
ManipulationPlanSharedDataConstPtr shared_data_
Definition: manipulation_plan.h:137
class_forward.h
pick_place::ManipulationPlanSharedData::end_effector_group_
const moveit::core::JointModelGroup * end_effector_group_
Definition: manipulation_plan.h:99
moveit::core::JointModelGroup
pick_place::ManipulationPlan::retreat_
moveit_msgs::GripperTranslation retreat_
Definition: manipulation_plan.h:143
pick_place::ManipulationPlan::clear
void clear()
Restore this plan to a state that makes it look like it never was processed by the manipulation pipel...
Definition: manipulation_plan.h:127
pick_place::ManipulationPlanSharedData::max_goal_sampling_attempts_
unsigned int max_goal_sampling_attempts_
Definition: manipulation_plan.h:102
pick_place::ManipulationPlan::goal_constraints_
moveit_msgs::Constraints goal_constraints_
Definition: manipulation_plan.h:155
pick_place::ManipulationPlan::approach_
moveit_msgs::GripperTranslation approach_
Definition: manipulation_plan.h:140
pick_place::ManipulationPlan::retreat_posture_
trajectory_msgs::JointTrajectory retreat_posture_
Definition: manipulation_plan.h:149
constraint_sampler.h
pick_place::ManipulationPlanSharedData::timeout_
ros::WallTime timeout_
Definition: manipulation_plan.h:112
pick_place::ManipulationPlan::error_code_
moveit_msgs::MoveItErrorCodes error_code_
Definition: manipulation_plan.h:168
pick_place::ManipulationPlan::transformed_goal_pose_
Eigen::Isometry3d transformed_goal_pose_
Definition: manipulation_plan.h:153


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:51