object_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_object_manipulation/ObjectDetectionAction.h>
35 #include <turtlebot_arm_object_manipulation/PickAndPlaceAction.h>
36 
38 
39 
40 using namespace visualization_msgs;
41 
42 const std::string arm_link = "/arm_base_link";
43 
44 
46 {
47 private:
49 
51 
52  // Actions
55 
56  turtlebot_arm_object_manipulation::ObjectDetectionGoal object_detection_goal_;
57  turtlebot_arm_object_manipulation::PickAndPlaceGoal pick_and_place_goal_;
58 
59  geometry_msgs::Pose old_pose_;
60 
61 public:
62 
64  server_("object_controls"),
65  object_detection_action_("object_detection", true),
66  pick_and_place_action_("pick_and_place", true)
67  {
68  server_.applyChanges();
69 
70  // Initialize goals
71  object_detection_goal_.frame = arm_link;
72 
73  pick_and_place_goal_.frame = arm_link;
74 
75  ROS_INFO("Finished initializing, waiting for servers...");
76 
77  object_detection_action_.waitForServer();
78  pick_and_place_action_.waitForServer();
79 
80  ROS_INFO("Found servers.");
81 
82  detectObjects();
83  }
84 
86  {
87  server_.clear();
88  server_.applyChanges();
89 
90  object_detection_action_.sendGoal(object_detection_goal_, boost::bind( &ObjectManipulationAction::addObjects, this, _1, _2));
91  }
92 
93  void addObjects(const actionlib::SimpleClientGoalState& state, const turtlebot_arm_object_manipulation::ObjectDetectionResultConstPtr& result)
94  {
95  ROS_INFO("Got object detection callback. Adding objects.");
96 
97  for (unsigned int i=0; i < result->obj_names.size(); i++)
98  {
99  // addObject(object.position.x, object.position.y, object.position.z, i); TODO
100  ROS_INFO("Added %d objects: '%s'", i, result->obj_names[i].c_str());
101  }
102 
103  server_.applyChanges();
104  }
105 
106 
107  // Move the real object!
108  void feedbackCb( const InteractiveMarkerFeedbackConstPtr &feedback )
109  {
110  switch ( feedback->event_type )
111  {
112  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
113  ROS_INFO_STREAM("Staging " << feedback->marker_name);
114  old_pose_ = feedback->pose;
115  break;
116 
117  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
118  ROS_INFO_STREAM("Now moving " << feedback->marker_name);
119  moveObject(old_pose_, feedback->pose);
120  detectObjects();
121  break;
122  }
123 
124  server_.applyChanges();
125  }
126 
127  bool moveObject(const geometry_msgs::Pose& start_pose, const geometry_msgs::Pose& end_pose)
128  {
129  pick_and_place_goal_.pick_pose = start_pose;
130  pick_and_place_goal_.place_pose = end_pose;
131  pick_and_place_action_.sendGoalAndWait(pick_and_place_goal_, ros::Duration(30.0), ros::Duration(30.0));
132 
133  if ( object_detection_action_.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
134  {
135  return true;
136  }
137  else
138  {
139  return false;
140  }
141  }
142 
143  // Make a box
144  Marker makeBox( InteractiveMarker &msg, float r, float g, float b )
145  {
146  Marker m;
147 
148  m.type = Marker::CUBE;
149  m.scale.x = msg.scale;
150  m.scale.y = msg.scale;
151  m.scale.z = msg.scale;
152  m.color.r = r;
153  m.color.g = g;
154  m.color.b = b;
155  m.color.a = 1.0;
156 
157  return m;
158  }
159 
160  // Add a new object
161  void addObject( float x, float y, float z, int n)
162  {
163  InteractiveMarker marker;
164  marker.header.frame_id = arm_link;
165  marker.pose.position.x = x;
166  marker.pose.position.y = y;
167  marker.pose.position.z = z;
168  marker.scale = 0.03;
169 
170  std::stringstream conv;
171  conv << n;
172  conv.str();
173 
174  marker.name = "object" + conv.str();
175 
176  InteractiveMarkerControl control;
177  control.orientation.w = 1;
178  control.orientation.x = 0;
179  control.orientation.y = 1;
180  control.orientation.z = 0;
181  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
182  marker.controls.push_back( control );
183 
184  control.markers.push_back( makeBox(marker, .5, .5, .5) );
185  control.always_visible = true;
186  marker.controls.push_back( control );
187 
188 
189  server_.insert( marker );
190  server_.setCallback( marker.name, boost::bind( &ObjectManipulationAction::feedbackCb, this, _1 ));
191  }
192 
193 };
194 
195 int main(int argc, char** argv)
196 {
197  // initialize node
198  ros::init(argc, argv, "object_manipulation");
199 
201 
202  // everything is done in cloud callback, just spin
203  ros::spin();
204 }
205 
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void addObjects(const actionlib::SimpleClientGoalState &state, const turtlebot_arm_object_manipulation::ObjectDetectionResultConstPtr &result)
actionlib::SimpleActionClient< turtlebot_arm_object_manipulation::ObjectDetectionAction > object_detection_action_
turtlebot_arm_object_manipulation::ObjectDetectionGoal object_detection_goal_
void addObject(float x, float y, float z, int n)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
turtlebot_arm_object_manipulation::PickAndPlaceGoal pick_and_place_goal_
ROSCPP_DECL void spin(Spinner &spinner)
Marker makeBox(InteractiveMarker &msg)
actionlib::SimpleActionClient< turtlebot_arm_object_manipulation::PickAndPlaceAction > pick_and_place_action_
#define ROS_INFO(...)
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
const std::string arm_link
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)
interactive_markers::InteractiveMarkerServer server_
Marker makeBox(InteractiveMarker &msg, float r, float g, float b)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
void feedbackCb(const InteractiveMarkerFeedbackConstPtr &feedback)
SimpleClientGoalState getState() const
bool moveObject(const geometry_msgs::Pose &start_pose, const geometry_msgs::Pose &end_pose)


turtlebot_arm_object_manipulation
Author(s): Jorge Santos
autogenerated on Fri Feb 7 2020 03:56:40