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 #include <ros/ros.h>
00031
00032 #include <actionlib/client/simple_action_client.h>
00033 #include <turtlebot_block_manipulation/BlockDetectionAction.h>
00034 #include <turtlebot_block_manipulation/PickAndPlaceAction.h>
00035 #include <turtlebot_block_manipulation/InteractiveBlockManipulationAction.h>
00036 #include <simple_arm_actions/ResetArmAction.h>
00037
00038 #include <string>
00039 #include <sstream>
00040
00041
00042 const std::string pick_and_place_topic = "/pick_and_place";
00043
00044 namespace turtlebot_block_manipulation
00045 {
00046
00047 class BlockManipulationAction
00048 {
00049 private:
00050 ros::NodeHandle nh_;
00051
00052
00053 actionlib::SimpleActionClient<BlockDetectionAction> block_detection_action_;
00054 actionlib::SimpleActionClient<InteractiveBlockManipulationAction> interactive_manipulation_action_;
00055 actionlib::SimpleActionClient<PickAndPlaceAction> pick_and_place_action_;
00056 actionlib::SimpleActionClient<simple_arm_actions::ResetArmAction> reset_arm_action_;
00057
00058 BlockDetectionGoal block_detection_goal_;
00059 InteractiveBlockManipulationGoal interactive_manipulation_goal_;
00060 PickAndPlaceGoal pick_and_place_goal_;
00061
00062
00063 std::string arm_link;
00064 double gripper_open;
00065 double gripper_closed;
00066 double z_up;
00067 double z_down;
00068 double block_size;
00069 bool once;
00070
00071 public:
00072
00073 BlockManipulationAction() :
00074 block_detection_action_("block_detection", true),
00075 interactive_manipulation_action_("interactive_manipulation", true),
00076 pick_and_place_action_("pick_and_place", true),
00077 reset_arm_action_("reset_arm", true)
00078 {
00079
00080 nh_.param<std::string>("arm_link", arm_link, "/arm_base_link");
00081 nh_.param<double>("gripper_open", gripper_open, 0.042);
00082 nh_.param<double>("gripper_closed", gripper_closed, 0.024);
00083 nh_.param<double>("z_up", z_up, 0.12);
00084 nh_.param<double>("table_height", z_down, 0.01);
00085 nh_.param<double>("block_size", block_size, 0.03);
00086
00087 nh_.param<bool>("once", once, false);
00088
00089
00090 block_detection_goal_.frame = arm_link;
00091 block_detection_goal_.table_height = z_down;
00092 block_detection_goal_.block_size = block_size;
00093
00094 pick_and_place_goal_.frame = arm_link;
00095 pick_and_place_goal_.z_up = z_up;
00096 pick_and_place_goal_.gripper_open = gripper_open;
00097 pick_and_place_goal_.gripper_closed = gripper_closed;
00098 pick_and_place_goal_.topic = pick_and_place_topic;
00099
00100 interactive_manipulation_goal_.block_size = block_size;
00101 interactive_manipulation_goal_.frame = arm_link;
00102
00103 ROS_INFO("Finished initializing, waiting for servers...");
00104
00105 block_detection_action_.waitForServer();
00106 ROS_INFO("Found block detection server.");
00107
00108 interactive_manipulation_action_.waitForServer();
00109 ROS_INFO("Found interactive manipulation.");
00110
00111 pick_and_place_action_.waitForServer();
00112 ROS_INFO("Found pick and place server.");
00113
00114 ROS_INFO("Found servers.");
00115
00116 reset_arm_action_.sendGoal(simple_arm_actions::ResetArmGoal());
00117
00118 detectBlocks();
00119 }
00120
00121 void detectBlocks()
00122 {
00123 block_detection_action_.sendGoal(block_detection_goal_, boost::bind( &BlockManipulationAction::addBlocks, this, _1, _2));
00124 }
00125
00126 void addBlocks(const actionlib::SimpleClientGoalState& state, const BlockDetectionResultConstPtr& result)
00127 {
00128 ROS_INFO("Got block detection callback. Adding blocks.");
00129 geometry_msgs::Pose block;
00130
00131 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00132 ROS_INFO("Succeeded!");
00133 else
00134 {
00135 ROS_INFO("Did not succeed! %s", state.toString().c_str());
00136 ros::shutdown();
00137 }
00138 interactive_manipulation_action_.sendGoal(interactive_manipulation_goal_, boost::bind( &BlockManipulationAction::pickAndPlace, this, _1, _2));
00139 }
00140
00141 void pickAndPlace(const actionlib::SimpleClientGoalState& state, const InteractiveBlockManipulationResultConstPtr& result)
00142 {
00143 ROS_INFO("Got interactive marker callback. Picking and placing.");
00144
00145 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00146 ROS_INFO("Succeeded!");
00147 else
00148 {
00149 ROS_INFO("Did not succeed! %s", state.toString().c_str());
00150 ros::shutdown();
00151 }
00152 pick_and_place_action_.sendGoal(pick_and_place_goal_, boost::bind( &BlockManipulationAction::finish, this, _1, _2));
00153 }
00154
00155 void finish(const actionlib::SimpleClientGoalState& state, const PickAndPlaceResultConstPtr& result)
00156 {
00157 ROS_INFO("Got pick and place callback. Finished!");
00158 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00159 ROS_INFO("Succeeded!");
00160 else
00161 ROS_INFO("Did not succeed! %s", state.toString().c_str());
00162
00163 reset_arm_action_.sendGoal(simple_arm_actions::ResetArmGoal());
00164
00165 if (once)
00166 ros::shutdown();
00167 else
00168 detectBlocks();
00169 }
00170 };
00171
00172 };
00173
00174 int main(int argc, char** argv)
00175 {
00176
00177 ros::init(argc, argv, "block_manipulation");
00178
00179
00180 turtlebot_block_manipulation::BlockManipulationAction manip;
00181
00182
00183 ros::spin();
00184 }
00185