interactive_manipulation_action_server.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  * Author: Michael Ferguson, Helen Oleynikova
30  */
31 
32 #include <ros/ros.h>
33 
36 
37 #include <turtlebot_arm_block_manipulation/InteractiveBlockManipulationAction.h>
38 #include <geometry_msgs/PoseArray.h>
39 
40 using namespace visualization_msgs;
41 
43 {
44 
46 {
47 private:
49 
51 
53  std::string action_name_;
54 
55  turtlebot_arm_block_manipulation::InteractiveBlockManipulationFeedback feedback_;
56  turtlebot_arm_block_manipulation::InteractiveBlockManipulationResult result_;
57  turtlebot_arm_block_manipulation::InteractiveBlockManipulationGoalConstPtr goal_;
58 
61 
62  geometry_msgs::Pose old_pose_;
63 
64  geometry_msgs::PoseArrayConstPtr msg_;
66 
67  // Parameters from goal
68  std::string arm_link;
69  double block_size;
70 
71  // Parameters from server
72  double bump_size;
73 
74 public:
75 
76  InteractiveManipulationServer(const std::string name) :
77  nh_("~"), server_("block_controls"), as_(name, false), action_name_(name), initialized_(false), block_size(0)
78  {
79  // Load parameters from the server.
80  nh_.param<double>("bump_size", bump_size, 0.005);
81 
82  // Register the goal and feeback callbacks.
83  as_.registerGoalCallback(boost::bind(&InteractiveManipulationServer::goalCB, this));
84  as_.registerPreemptCallback(boost::bind(&InteractiveManipulationServer::preemptCB, this));
85 
86  as_.start();
87 
88  block_sub_ = nh_.subscribe("/turtlebot_blocks", 1, &InteractiveManipulationServer::addBlocks, this);
89  pick_and_place_pub_ = nh_.advertise< geometry_msgs::PoseArray >("/pick_and_place", 1, true);
90  }
91 
92  void goalCB()
93  {
94 
95  // accept the new goal
96  goal_ = as_.acceptNewGoal();
97 
98  ROS_INFO("[interactive manipulation] Received goal! %f, %s", goal_->block_size, goal_->frame.c_str());
99 
100  block_size = goal_->block_size;
101  arm_link = goal_->frame;
102 
103  if (initialized_)
104  addBlocks(msg_);
105  }
106 
107  void preemptCB()
108  {
109  ROS_INFO("%s: Preempted", action_name_.c_str());
110  // set the action state to preempted
111  as_.setPreempted();
112  }
113 
114  void addBlocks(const geometry_msgs::PoseArrayConstPtr& msg)
115  {
116  server_.clear();
117  server_.applyChanges();
118 
119  ROS_INFO("Got block detection callback. Adding blocks.");
120  geometry_msgs::Pose block;
121  bool active = as_.isActive();
122 
123  for (unsigned int i=0; i < msg->poses.size(); i++)
124  {
125  block = msg->poses[i];
126  addBlock(block, i, active, msg->header.frame_id);
127  ROS_INFO("Added %d blocks", i);
128  }
129 
130  server_.applyChanges();
131 
132  msg_ = msg;
133  initialized_ = true;
134  }
135 
136 
137  // Move the real block!
138  void feedbackCb( const InteractiveMarkerFeedbackConstPtr &feedback )
139  {
140  if (!as_.isActive())
141  {
142  ROS_INFO("Got feedback but not active!");
143  return;
144  }
145  switch ( feedback->event_type )
146  {
147  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
148  ROS_INFO_STREAM("Staging " << feedback->marker_name);
149  old_pose_ = feedback->pose;
150  break;
151 
152  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
153  ROS_INFO_STREAM("Now moving " << feedback->marker_name);
154  moveBlock(old_pose_, feedback->pose);
155  break;
156  }
157 
158  server_.applyChanges();
159  }
160 
161  void moveBlock(const geometry_msgs::Pose& start_pose, const geometry_msgs::Pose& end_pose)
162  {
163  // Return pickup and place poses as the result of the action
164  geometry_msgs::Pose start_pose_bumped, end_pose_bumped;
165  start_pose_bumped = start_pose;
166  // start_pose_bumped.position.y -= bump_size; TODO/WARN: this was in the original version, but destroys piss off indigo/moveit operation!
167  start_pose_bumped.position.z -= block_size/2.0 - bump_size;
168 
169  result_.pickup_pose = start_pose_bumped;
170 
171  end_pose_bumped = end_pose;
172  end_pose_bumped.position.z -= block_size/2.0 - bump_size;
173  result_.place_pose = end_pose_bumped;
174 
175  // Publish pickup and place poses for visualizing on RViz
176  geometry_msgs::PoseArray msg;
177  msg.header.frame_id = arm_link;
178  msg.header.stamp = ros::Time::now();
179  msg.poses.push_back(start_pose_bumped);
180  msg.poses.push_back(end_pose_bumped);
181 
182  pick_and_place_pub_.publish(msg);
183 
184  as_.setSucceeded(result_);
185 
186  server_.clear();
187  server_.applyChanges();
188  }
189 
190  // Make a box
191  Marker makeBox( InteractiveMarker &msg, float r, float g, float b )
192  {
193  Marker m;
194 
195  m.type = Marker::CUBE;
196  m.scale.x = msg.scale;
197  m.scale.y = msg.scale;
198  m.scale.z = msg.scale;
199  m.color.r = r;
200  m.color.g = g;
201  m.color.b = b;
202  m.color.a = 1.0;
203 
204  return m;
205  }
206 
207  // Add a new block
208  void addBlock( const geometry_msgs::Pose pose, int n, bool active, std::string link)
209  {
210  InteractiveMarker marker;
211  marker.header.frame_id = link;
212  marker.pose = pose;
213  marker.scale = block_size;
214 
215  std::stringstream conv;
216  conv << n;
217  conv.str();
218 
219  marker.name = "block" + conv.str();
220 
221  InteractiveMarkerControl control;
222  control.orientation.w = 1;
223  control.orientation.x = 0;
224  control.orientation.y = 1;
225  control.orientation.z = 0;
226  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
227 
228  if (active)
229  marker.controls.push_back( control );
230 
231  control.markers.push_back( makeBox(marker, .5, .5, .5) );
232  control.always_visible = true;
233  marker.controls.push_back( control );
234 
235 
236  server_.insert( marker );
237  server_.setCallback( marker.name, boost::bind( &InteractiveManipulationServer::feedbackCb, this, _1 ));
238  }
239 
240 };
241 
242 };
243 
244 int main(int argc, char** argv)
245 {
246  // initialize node
247  ros::init(argc, argv, "interactive_manipulation_action_server");
248 
249  turtlebot_arm_block_manipulation::InteractiveManipulationServer manip("interactive_manipulation");
250 
251  ros::spin();
252 }
253 
boost::shared_ptr< const Goal > acceptNewGoal()
turtlebot_arm_block_manipulation::InteractiveBlockManipulationGoalConstPtr goal_
void publish(const boost::shared_ptr< M > &message) const
void addBlock(const geometry_msgs::Pose pose, int n, bool active, std::string link)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
Marker makeBox(InteractiveMarker &msg)
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void moveBlock(const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)
void registerPreemptCallback(boost::function< void()> cb)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
turtlebot_arm_block_manipulation::InteractiveBlockManipulationResult result_
actionlib::SimpleActionServer< turtlebot_arm_block_manipulation::InteractiveBlockManipulationAction > as_
void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
turtlebot_arm_block_manipulation::InteractiveBlockManipulationFeedback feedback_
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
static Time now()
void registerGoalCallback(boost::function< void()> cb)
const std::string arm_link
const double block_size


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