pick_place_task.h
Go to the documentation of this file.
1 /*********************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019 PickNik LLC.
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *********************************************************************/
32 
33 /* Author: Henning Kayser, Simon Goldstein
34  Desc: A demo to show MoveIt Task Constructor in action
35 */
36 
37 // ROS
38 #include <ros/ros.h>
39 
40 // MoveIt
44 
45 // MTC
59 #include <moveit_task_constructor_msgs/ExecuteTaskSolutionAction.h>
60 
61 #pragma once
62 
64 using namespace moveit::task_constructor;
65 
66 // prepare a demo environment from ROS parameters under pnh
68 
69 class PickPlaceTask
70 {
71 public:
72  PickPlaceTask(const std::string& task_name, const ros::NodeHandle& pnh);
73  ~PickPlaceTask() = default;
74 
75  bool init();
76 
77  bool plan();
78 
79  bool execute();
80 
81 private:
82  void loadParameters();
83 
84  static constexpr char LOGNAME[]{ "pick_place_task" };
85 
86  ros::NodeHandle pnh_;
87 
88  std::string task_name_;
89  moveit::task_constructor::TaskPtr task_;
90 
91  // planning group properties
92  std::string arm_group_name_;
93  std::string eef_name_;
94  std::string hand_group_name_;
95  std::string hand_frame_;
96 
97  // object + surface
98  std::vector<std::string> support_surfaces_;
99  std::string object_reference_frame_;
100  std::string surface_link_;
101  std::string object_name_;
102  std::string world_frame_;
103  std::vector<double> object_dimensions_;
104 
105  // Predefined pose targets
106  std::string hand_open_pose_;
107  std::string hand_close_pose_;
108  std::string arm_home_pose_;
109 
110  // Pick metrics
111  Eigen::Isometry3d grasp_frame_transform_;
112  double approach_object_min_dist_;
113  double approach_object_max_dist_;
114  double lift_object_min_dist_;
115  double lift_object_max_dist_;
116 
117  // Place metrics
118  geometry_msgs::Pose place_pose_;
119  double place_surface_offset_;
120 };
121 } // namespace moveit_task_constructor_demo
robot_model.h
pipeline_planner.h
moveit_task_constructor_demo
Definition: pick_place_task.h:63
ros.h
move_to.h
connect.h
modify_planning_scene.h
predicate_filter.h
generate_grasp_pose.h
move_relative.h
current_state.h
moveit::task_constructor
task.h
generate_place_pose.h
compute_ik.h
moveit_task_constructor_demo::PickPlaceTask
Definition: pick_place_task.h:99
execute
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
planning_scene_interface.h
moveit_task_constructor_demo::LOGNAME
constexpr char LOGNAME[]
Definition: pick_place_task.cpp:72
planning_scene.h
cartesian_path.h
init
void init(const M_string &remappings)
moveit_task_constructor_demo::setupDemoScene
void setupDemoScene(ros::NodeHandle &pnh)
Definition: pick_place_task.cpp:124
generate_pose.h
ros::NodeHandle


demo
Author(s): Robert Haschke , Simon Goldstein , Henning Kayser
autogenerated on Sat May 3 2025 02:40:30