$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * \author E. Gil Jones 00036 *********************************************************************/ 00037 00038 #include <stdio.h> 00039 #include <stdlib.h> 00040 #include <time.h> 00041 #include <boost/thread.hpp> 00042 00043 #include <ros/ros.h> 00044 #include <actionlib/client/simple_action_client.h> 00045 #include <actionlib/server/simple_action_server.h> 00046 #include <collision_environment_msgs/MakeStaticCollisionMapAction.h> 00047 #include <pr2_msgs/SetPeriodicCmd.h> 00048 #include <cotesys_ros_grasping/TakeStaticCollisionMapAction.h> 00049 00050 namespace cotesys_ros_grasping 00051 { 00052 00053 class TakeStaticCollisionMapServer 00054 { 00055 00056 public: 00057 TakeStaticCollisionMapServer(); 00058 00059 bool execute(const cotesys_ros_grasping::TakeStaticCollisionMapGoalConstPtr& goal); 00060 00061 private: 00062 00063 boost::shared_ptr<actionlib::SimpleActionClient<collision_environment_msgs::MakeStaticCollisionMapAction> > make_static_client_; 00064 boost::shared_ptr<actionlib::SimpleActionServer<cotesys_ros_grasping::TakeStaticCollisionMapAction> > action_server_; 00065 00066 ros::ServiceClient set_laser_client_; 00067 ros::NodeHandle priv_nh_, root_nh_; 00068 00069 std::string cloud_source_; 00070 double laser_period_, laser_amplitude_, laser_offset_; 00071 }; 00072 00073 TakeStaticCollisionMapServer::TakeStaticCollisionMapServer() 00074 : priv_nh_("~") 00075 { 00076 priv_nh_.param<double>("laser_period", laser_period_, 2); 00077 priv_nh_.param<double>("laser_amplitude", laser_amplitude_, .25); 00078 priv_nh_.param<double>("laser_offset", laser_offset_, .7); 00079 priv_nh_.param<std::string>("cloud_source", cloud_source_, "full_cloud_filtered"); 00080 00081 ros::service::waitForService("/laser_tilt_controller/set_periodic_cmd"); 00082 set_laser_client_ = root_nh_.serviceClient<pr2_msgs::SetPeriodicCmd>("/laser_tilt_controller/set_periodic_cmd"); 00083 00084 make_static_client_.reset(new actionlib::SimpleActionClient<collision_environment_msgs::MakeStaticCollisionMapAction>("/make_static_collision_map", true)); 00085 00086 action_server_.reset(new actionlib::SimpleActionServer<cotesys_ros_grasping::TakeStaticCollisionMapAction>(root_nh_, "take_static_collision_map", 00087 boost::bind(&TakeStaticCollisionMapServer::execute, this, _1))); 00088 } 00089 00090 bool TakeStaticCollisionMapServer::execute(const cotesys_ros_grasping::TakeStaticCollisionMapGoalConstPtr& goal) 00091 { 00092 collision_environment_msgs::MakeStaticCollisionMapGoal stat_goal; 00093 stat_goal.cloud_source = cloud_source_; 00094 stat_goal.number_of_clouds = 2; 00095 make_static_client_->sendGoal(stat_goal); 00096 00097 pr2_msgs::SetPeriodicCmd::Request laser_req; 00098 laser_req.command.header.stamp = ros::Time::now(); 00099 laser_req.command.profile = "linear"; 00100 laser_req.command.period = laser_period_; 00101 laser_req.command.amplitude = laser_amplitude_; 00102 laser_req.command.offset = laser_offset_; 00103 00104 cotesys_ros_grasping::TakeStaticCollisionMapResult res; 00105 00106 pr2_msgs::SetPeriodicCmd::Response laser_res; 00107 if(!set_laser_client_.call(laser_req, laser_res)) { 00108 ROS_WARN("Something wrong with laser"); 00109 res.success = false; 00110 action_server_->setAborted(res); 00111 return true; 00112 } 00113 00114 make_static_client_->waitForResult(); 00115 res.success = false; 00116 action_server_->setSucceeded(res); 00117 00118 return true; 00119 } 00120 00121 } 00122 00123 int main(int argc, char** argv) 00124 { 00125 ros::init(argc, argv, "take_static_collision_map"); 00126 00127 ros::AsyncSpinner spinner(1); // Use 1 thread 00128 spinner.start(); 00129 00130 cotesys_ros_grasping::TakeStaticCollisionMapServer take_static_map; 00131 00132 ROS_INFO("Take static collision map started"); 00133 ros::waitForShutdown(); 00134 00135 return 0; 00136 }