Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <ros/ros.h>
00033
00034 #include <actionlib/server/simple_action_server.h>
00035 #include <interactive_markers/interactive_marker_server.h>
00036
00037 #include <turtlebot_block_manipulation/InteractiveBlockManipulationAction.h>
00038 #include <geometry_msgs/PoseArray.h>
00039
00040 using namespace visualization_msgs;
00041
00042 namespace turtlebot_block_manipulation
00043 {
00044
00045 class InteractiveManipulationServer
00046 {
00047 private:
00048 ros::NodeHandle nh_;
00049
00050 interactive_markers::InteractiveMarkerServer server_;
00051
00052 actionlib::SimpleActionServer<turtlebot_block_manipulation::InteractiveBlockManipulationAction> as_;
00053 std::string action_name_;
00054
00055 turtlebot_block_manipulation::InteractiveBlockManipulationFeedback feedback_;
00056 turtlebot_block_manipulation::InteractiveBlockManipulationResult result_;
00057 turtlebot_block_manipulation::InteractiveBlockManipulationGoalConstPtr goal_;
00058
00059 ros::Subscriber block_sub_;
00060 ros::Publisher pick_and_place_pub_;
00061
00062 geometry_msgs::Pose old_pose_;
00063
00064 geometry_msgs::PoseArrayConstPtr msg_;
00065 bool initialized_;
00066
00067
00068 std::string arm_link;
00069 double block_size;
00070
00071
00072 double bump_size;
00073
00074 public:
00075
00076 InteractiveManipulationServer(const std::string name) :
00077 nh_("~"), server_("block_controls"), as_(name, false), action_name_(name), initialized_(false), block_size(0)
00078 {
00079
00080 nh_.param<double>("bump_size", bump_size, 0.005);
00081
00082
00083 as_.registerGoalCallback(boost::bind(&InteractiveManipulationServer::goalCB, this));
00084 as_.registerPreemptCallback(boost::bind(&InteractiveManipulationServer::preemptCB, this));
00085
00086 as_.start();
00087
00088 block_sub_ = nh_.subscribe("/turtlebot_blocks", 1, &InteractiveManipulationServer::addBlocks, this);
00089 pick_and_place_pub_ = nh_.advertise< geometry_msgs::PoseArray >("/pick_and_place", 1, true);
00090 }
00091
00092 void goalCB()
00093 {
00094
00095
00096 goal_ = as_.acceptNewGoal();
00097
00098 ROS_INFO("[interactive manipulation] Received goal! %f, %s", goal_->block_size, goal_->frame.c_str());
00099
00100 block_size = goal_->block_size;
00101 arm_link = goal_->frame;
00102
00103 if (initialized_)
00104 addBlocks(msg_);
00105 }
00106
00107 void preemptCB()
00108 {
00109 ROS_INFO("%s: Preempted", action_name_.c_str());
00110
00111 as_.setPreempted();
00112 }
00113
00114 void addBlocks(const geometry_msgs::PoseArrayConstPtr& msg)
00115 {
00116 server_.clear();
00117 server_.applyChanges();
00118
00119 ROS_INFO("Got block detection callback. Adding blocks.");
00120 geometry_msgs::Pose block;
00121 bool active = as_.isActive();
00122
00123 for (unsigned int i=0; i < msg->poses.size(); i++)
00124 {
00125 block = msg->poses[i];
00126 addBlock(block, i, active, msg->header.frame_id);
00127 ROS_INFO("Added %d blocks", i);
00128 }
00129
00130 server_.applyChanges();
00131
00132 msg_ = msg;
00133 initialized_ = true;
00134 }
00135
00136
00137
00138 void feedbackCb( const InteractiveMarkerFeedbackConstPtr &feedback )
00139 {
00140 if (!as_.isActive())
00141 {
00142 ROS_INFO("Got feedback but not active!");
00143 return;
00144 }
00145 switch ( feedback->event_type )
00146 {
00147 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
00148 ROS_INFO_STREAM("Staging " << feedback->marker_name);
00149 old_pose_ = feedback->pose;
00150 break;
00151
00152 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
00153 ROS_INFO_STREAM("Now moving " << feedback->marker_name);
00154 moveBlock(old_pose_, feedback->pose);
00155 break;
00156 }
00157
00158 server_.applyChanges();
00159 }
00160
00161 void moveBlock(const geometry_msgs::Pose& start_pose, const geometry_msgs::Pose& end_pose)
00162 {
00163 geometry_msgs::Pose start_pose_bumped, end_pose_bumped;
00164 start_pose_bumped = start_pose;
00165 start_pose_bumped.position.y -= bump_size;
00166 start_pose_bumped.position.z -= block_size/2.0 - bump_size;
00167 result_.pickup_pose = start_pose_bumped;
00168
00169 end_pose_bumped = end_pose;
00170 end_pose_bumped.position.z -= block_size/2.0 - bump_size;
00171 result_.place_pose = end_pose_bumped;
00172
00173 geometry_msgs::PoseArray msg;
00174 msg.header.frame_id = arm_link;
00175 msg.header.stamp = ros::Time::now();
00176 msg.poses.push_back(start_pose_bumped);
00177 msg.poses.push_back(end_pose_bumped);
00178
00179 pick_and_place_pub_.publish(msg);
00180
00181 as_.setSucceeded(result_);
00182
00183 server_.clear();
00184 server_.applyChanges();
00185 }
00186
00187
00188 Marker makeBox( InteractiveMarker &msg, float r, float g, float b )
00189 {
00190 Marker m;
00191
00192 m.type = Marker::CUBE;
00193 m.scale.x = msg.scale;
00194 m.scale.y = msg.scale;
00195 m.scale.z = msg.scale;
00196 m.color.r = r;
00197 m.color.g = g;
00198 m.color.b = b;
00199 m.color.a = 1.0;
00200
00201 return m;
00202 }
00203
00204
00205 void addBlock( const geometry_msgs::Pose pose, int n, bool active, std::string link)
00206 {
00207 InteractiveMarker marker;
00208 marker.header.frame_id = link;
00209 marker.pose = pose;
00210 marker.scale = block_size;
00211
00212 std::stringstream conv;
00213 conv << n;
00214 conv.str();
00215
00216 marker.name = "block" + conv.str();
00217
00218 InteractiveMarkerControl control;
00219 control.orientation.w = 1;
00220 control.orientation.x = 0;
00221 control.orientation.y = 1;
00222 control.orientation.z = 0;
00223 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
00224
00225 if (active)
00226 marker.controls.push_back( control );
00227
00228 control.markers.push_back( makeBox(marker, .5, .5, .5) );
00229 control.always_visible = true;
00230 marker.controls.push_back( control );
00231
00232
00233 server_.insert( marker );
00234 server_.setCallback( marker.name, boost::bind( &InteractiveManipulationServer::feedbackCb, this, _1 ));
00235 }
00236
00237 };
00238
00239 };
00240
00241 int main(int argc, char** argv)
00242 {
00243
00244 ros::init(argc, argv, "interactive_manipulation_action_server");
00245
00246 turtlebot_block_manipulation::InteractiveManipulationServer manip("interactive_manipulation");
00247
00248 ros::spin();
00249 }
00250