block_manipulation_demo.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 
33 #include <turtlebot_arm_block_manipulation/BlockDetectionAction.h>
34 #include <turtlebot_arm_block_manipulation/PickAndPlaceAction.h>
35 #include <turtlebot_arm_block_manipulation/InteractiveBlockManipulationAction.h>
36 
37 #include <string>
38 #include <sstream>
39 
40 
41 const std::string pick_and_place_topic = "/pick_and_place";
42 
44 {
45 
47 {
48 private:
50 
51  // Actions and services
55 
56  BlockDetectionGoal block_detection_goal_;
57  InteractiveBlockManipulationGoal interactive_manipulation_goal_;
58  PickAndPlaceGoal pick_and_place_goal_;
59 
60  // Parameters
61  std::string arm_link;
62  double gripper_open;
64  double z_up;
65  double z_down;
66  double block_size;
67  bool once;
68 
69 public:
70 
72  block_detection_action_("block_detection", true),
73  interactive_manipulation_action_("interactive_manipulation", true),
74  pick_and_place_action_("pick_and_place", true)
75  {
76  // Load parameters
77  nh_.param<std::string>("arm_link", arm_link, "/arm_link");
78  nh_.param<double>("gripper_open", gripper_open, 0.042);
79  nh_.param<double>("gripper_closed", gripper_closed, 0.024);
80  nh_.param<double>("z_up", z_up, 0.12);
81  nh_.param<double>("table_height", z_down, 0.01);
82  nh_.param<double>("block_size", block_size, 0.03);
83 
84  nh_.param<bool>("once", once, false);
85 
86  // Initialize goals
87  block_detection_goal_.frame = arm_link;
88  block_detection_goal_.table_height = z_down;
89  block_detection_goal_.block_size = block_size;
90 
91  pick_and_place_goal_.frame = arm_link;
92  pick_and_place_goal_.z_up = z_up;
93  pick_and_place_goal_.gripper_open = gripper_open;
94  pick_and_place_goal_.gripper_closed = gripper_closed;
95  pick_and_place_goal_.topic = pick_and_place_topic;
96 
97  interactive_manipulation_goal_.block_size = block_size;
98  interactive_manipulation_goal_.frame = arm_link;
99 
100  ROS_INFO("Finished initializing, waiting for servers...");
101 
102  block_detection_action_.waitForServer();
103  ROS_INFO("Found block detection server.");
104 
105  interactive_manipulation_action_.waitForServer();
106  ROS_INFO("Found interactive manipulation.");
107 
108  pick_and_place_action_.waitForServer();
109  ROS_INFO("Found pick and place server.");
110 
111  ROS_INFO("Found servers.");
112  }
113 
115  {
116  block_detection_action_.sendGoal(block_detection_goal_, boost::bind( &BlockManipulationAction::addBlocks, this, _1, _2));
117  }
118 
119  void addBlocks(const actionlib::SimpleClientGoalState& state, const BlockDetectionResultConstPtr& result)
120  {
121  ROS_INFO("Got block detection callback. Adding blocks.");
122  geometry_msgs::Pose block;
123 
125  ROS_INFO("Succeeded!");
126  else
127  {
128  ROS_INFO("Did not succeed! %s", state.toString().c_str());
129  ros::shutdown();
130  }
131  interactive_manipulation_action_.sendGoal(interactive_manipulation_goal_, boost::bind( &BlockManipulationAction::pickAndPlace, this, _1, _2));
132  }
133 
134  void pickAndPlace(const actionlib::SimpleClientGoalState& state, const InteractiveBlockManipulationResultConstPtr& result)
135  {
136  ROS_INFO("Got interactive marker callback. Picking and placing.");
137 
139  ROS_INFO("Succeeded!");
140  else
141  {
142  ROS_INFO("Did not succeed! %s", state.toString().c_str());
143  ros::shutdown();
144  }
145  pick_and_place_action_.sendGoal(pick_and_place_goal_, boost::bind( &BlockManipulationAction::finish, this, _1, _2));
146  }
147 
148  void finish(const actionlib::SimpleClientGoalState& state, const PickAndPlaceResultConstPtr& result)
149  {
150  ROS_INFO("Got pick and place callback. Finished!");
152  ROS_INFO("Succeeded!");
153  else
154  ROS_INFO("Did not succeed! %s", state.toString().c_str());
155 
156  if (once)
157  ros::shutdown();
158  else
159  detectBlocks();
160  }
161 };
162 
163 };
164 
165 int main(int argc, char** argv)
166 {
167  // initialize node
168  ros::init(argc, argv, "block_manipulation");
169 
171 
172  // Setup an asynchronous spinner as the move groups operations need continuous spinning
174  spinner.start();
175 
176  while (ros::ok())
177  {
178  manip.detectBlocks();
179 
180  // Allow user restarting, for the case that the block detection fails
181  std::cout << "Press Enter for restarting block detection" << std::endl;
182  std::cin.ignore();
183  }
184 
185  spinner.stop();
186 }
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
actionlib::SimpleActionClient< BlockDetectionAction > block_detection_action_
void pickAndPlace(const actionlib::SimpleClientGoalState &state, const InteractiveBlockManipulationResultConstPtr &result)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void finish(const actionlib::SimpleClientGoalState &state, const PickAndPlaceResultConstPtr &result)
const std::string pick_and_place_topic
void spinner()
std::string toString() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void addBlocks(const actionlib::SimpleClientGoalState &state, const BlockDetectionResultConstPtr &result)
actionlib::SimpleActionClient< PickAndPlaceAction > pick_and_place_action_
ROSCPP_DECL void shutdown()
actionlib::SimpleActionClient< InteractiveBlockManipulationAction > interactive_manipulation_action_


turtlebot_arm_block_manipulation
Author(s): Michael Ferguson, Helen Oleynikova
autogenerated on Fri Feb 7 2020 03:56:21