block_manipulation_actions.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 
31 #include <ros/ros.h>
32 
34 #include <turtlebot_arm_block_manipulation/BlockDetectionAction.h>
35 #include <turtlebot_arm_block_manipulation/PickAndPlaceAction.h>
36 
38 
39 
40 using namespace visualization_msgs;
41 
42 const std::string arm_link = "/arm_base_link";
43 const double gripper_open = 0.042;
44 const double gripper_closed = 0.024;
45 
46 const double z_up = 0.08;
47 const double z_down = -0.05;
48 
49 const double block_size = 0.0127;
50 
51 
53 {
54 private:
56 
58 
59  // Actions
62 
63  turtlebot_arm_block_manipulation::BlockDetectionGoal block_detection_goal_;
64  turtlebot_arm_block_manipulation::PickAndPlaceGoal pick_and_place_goal_;
65 
66  geometry_msgs::Pose old_pose_;
67 
68 public:
69 
71  server_("block_controls"),
72  block_detection_action_("block_detection", true),
73  pick_and_place_action_("pick_and_place", true)
74  {
75  server_.applyChanges();
76 
77  // Initialize goals
78  block_detection_goal_.frame = arm_link;
79  block_detection_goal_.table_height = z_down;
80  block_detection_goal_.block_size = block_size;
81 
82  pick_and_place_goal_.frame = arm_link;
83  pick_and_place_goal_.z_up = z_up;
84  pick_and_place_goal_.gripper_open = gripper_open;
85  pick_and_place_goal_.gripper_closed = gripper_closed;
86 
87  ROS_INFO("Finished initializing, waiting for servers...");
88 
89  block_detection_action_.waitForServer();
90  pick_and_place_action_.waitForServer();
91 
92  ROS_INFO("Found servers.");
93 
94  detectBlocks();
95  }
96 
97  void detectBlocks()
98  {
99  server_.clear();
100  server_.applyChanges();
101 
102  block_detection_action_.sendGoal(block_detection_goal_, boost::bind( &BlockManipulationAction::addBlocks, this, _1, _2));
103  }
104 
105  void addBlocks(const actionlib::SimpleClientGoalState& state, const turtlebot_arm_block_manipulation::BlockDetectionResultConstPtr& result)
106  {
107  ROS_INFO("Got block detection callback. Adding blocks.");
108  geometry_msgs::Pose block;
109 
110  for (unsigned int i=0; i < result->blocks.poses.size(); i++)
111  {
112  block = result->blocks.poses[i];
113  addBlock(block.position.x, block.position.y, block.position.z, i);
114  ROS_INFO("Added %d blocks", i);
115  }
116 
117  server_.applyChanges();
118  }
119 
120 
121  // Move the real block!
122  void feedbackCb( const InteractiveMarkerFeedbackConstPtr &feedback )
123  {
124  switch ( feedback->event_type )
125  {
126  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
127  ROS_INFO_STREAM("Staging " << feedback->marker_name);
128  old_pose_ = feedback->pose;
129  break;
130 
131  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
132  ROS_INFO_STREAM("Now moving " << feedback->marker_name);
133  moveBlock(old_pose_, feedback->pose);
134  detectBlocks();
135  break;
136  }
137 
138  server_.applyChanges();
139  }
140 
141  bool moveBlock(const geometry_msgs::Pose& start_pose, const geometry_msgs::Pose& end_pose)
142  {
143  pick_and_place_goal_.pickup_pose = start_pose;
144  pick_and_place_goal_.place_pose = end_pose;
145  pick_and_place_action_.sendGoalAndWait(pick_and_place_goal_, ros::Duration(30.0), ros::Duration(30.0));
146  //pick_and_place_action_.sendGoal(pick_and_place_goal_);
147  //pick_and_place_action_.waitForResult(ros::Duration(30.0));
148 
149  if ( block_detection_action_.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
150  {
151  return true;
152  }
153  else
154  {
155  return false;
156  }
157  }
158 
159  // Make a box
160  Marker makeBox( InteractiveMarker &msg, float r, float g, float b )
161  {
162  Marker m;
163 
164  m.type = Marker::CUBE;
165  m.scale.x = msg.scale;
166  m.scale.y = msg.scale;
167  m.scale.z = msg.scale;
168  m.color.r = r;
169  m.color.g = g;
170  m.color.b = b;
171  m.color.a = 1.0;
172 
173  return m;
174  }
175 
176  // Add a new block
177  void addBlock( float x, float y, float z, int n)
178  {
179  InteractiveMarker marker;
180  marker.header.frame_id = arm_link;
181  marker.pose.position.x = x;
182  marker.pose.position.y = y;
183  marker.pose.position.z = z;
184  marker.scale = 0.03;
185 
186  std::stringstream conv;
187  conv << n;
188  conv.str();
189 
190  marker.name = "block" + conv.str();
191 
192  InteractiveMarkerControl control;
193  control.orientation.w = 1;
194  control.orientation.x = 0;
195  control.orientation.y = 1;
196  control.orientation.z = 0;
197  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
198  marker.controls.push_back( control );
199 
200  control.markers.push_back( makeBox(marker, .5, .5, .5) );
201  control.always_visible = true;
202  marker.controls.push_back( control );
203 
204 
205  server_.insert( marker );
206  server_.setCallback( marker.name, boost::bind( &BlockManipulationAction::feedbackCb, this, _1 ));
207  }
208 
209 };
210 
211 int main(int argc, char** argv)
212 {
213  // initialize node
214  ros::init(argc, argv, "block_manipulation");
215 
217 
218  // everything is done in cloud callback, just spin
219  ros::spin();
220 }
221 
turtlebot_arm_block_manipulation::BlockDetectionGoal block_detection_goal_
int main(int argc, char **argv)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void addBlock(float x, float y, float z, int n)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void feedbackCb(const InteractiveMarkerFeedbackConstPtr &feedback)
const double z_up
actionlib::SimpleActionClient< turtlebot_arm_block_manipulation::BlockDetectionAction > block_detection_action_
turtlebot_arm_block_manipulation::PickAndPlaceGoal pick_and_place_goal_
ROSCPP_DECL void spin(Spinner &spinner)
const double z_down
Marker makeBox(InteractiveMarker &msg)
#define ROS_INFO(...)
const double gripper_closed
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
const double gripper_open
interactive_markers::InteractiveMarkerServer server_
const std::string arm_link
void addBlocks(const actionlib::SimpleClientGoalState &state, const turtlebot_arm_block_manipulation::BlockDetectionResultConstPtr &result)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
SimpleClientGoalState getState() const
const double block_size
actionlib::SimpleActionClient< turtlebot_arm_block_manipulation::PickAndPlaceAction > pick_and_place_action_
bool moveBlock(const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)
Marker makeBox(InteractiveMarker &msg, float r, float g, float b)


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