$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * 00035 *********************************************************************/ 00036 00037 /* \author: Sachin Chitta */ 00038 00039 #include <ros/ros.h> 00040 #include <arm_navigation_msgs/MakeStaticCollisionMapAction.h> 00041 #include <actionlib/client/simple_action_client.h> 00042 #include <arm_navigation_msgs/Shape.h> 00043 #include <pr2_msgs/SetPeriodicCmd.h> 00044 #include <sensor_msgs/PointCloud.h> 00045 #include <tf/transform_datatypes.h> 00046 00047 00048 namespace arm_navigation_utils 00049 { 00050 00051 static const std::string MAKE_STATIC_COLLISION_MAP_ACTION_NAME = "make_static_collision_map"; 00052 static const std::string TILT_LASER_PERIODIC_COMMAND_NAME = "laser_tilt_controller/set_periodic_cmd"; 00053 00054 class ArmNavigationUtils 00055 { 00056 public: 00057 00058 ArmNavigationUtils() : 00059 root_nh_(""), 00060 make_static_collision_map_client_(root_nh_, MAKE_STATIC_COLLISION_MAP_ACTION_NAME, true) 00061 { 00062 while ( !ros::service::waitForService(TILT_LASER_PERIODIC_COMMAND_NAME, ros::Duration(2.0)) && 00063 root_nh_.ok() ) 00064 { 00065 ROS_INFO("Waiting for tilt laser periodic command service to come up"); 00066 } 00067 tilt_laser_service_ = root_nh_.serviceClient<pr2_msgs::SetPeriodicCmd>(TILT_LASER_PERIODIC_COMMAND_NAME); 00068 00069 while(!make_static_collision_map_client_.waitForServer(ros::Duration(2.0)) 00070 && root_nh_.ok()){ 00071 ROS_INFO("Waiting for the make static collision map action to come up"); 00072 } 00073 00074 //cribbed from motion planning laser settings 00075 laser_slow_period_ = 5; 00076 laser_slow_amplitude_ = 1.02; 00077 laser_slow_offset_ = .31; 00078 00079 //cribbed from head cart tilt_laser_launch 00080 laser_fast_period_ = 2; 00081 laser_fast_amplitude_ = .6; 00082 laser_fast_offset_ = .25; 00083 } 00084 ~ArmNavigationUtils(){} 00085 00086 bool setLaserScan(bool fast) 00087 { 00088 pr2_msgs::SetPeriodicCmd::Request req; 00089 pr2_msgs::SetPeriodicCmd::Response res; 00090 00091 req.command.profile = "linear"; 00092 if(fast) 00093 { 00094 req.command.period = laser_fast_period_; 00095 req.command.amplitude = laser_fast_amplitude_; 00096 req.command.offset = laser_fast_offset_; 00097 } 00098 else 00099 { 00100 req.command.period = laser_slow_period_; 00101 req.command.amplitude = laser_slow_amplitude_; 00102 req.command.offset = laser_slow_offset_; 00103 } 00104 00105 if(!tilt_laser_service_.call(req,res)) 00106 { 00107 ROS_ERROR("Tilt laser service call failed.\n"); 00108 return false; 00109 } 00110 return true; 00111 } 00112 00113 bool takeStaticMap() 00114 { 00115 arm_navigation_msgs::MakeStaticCollisionMapGoal static_map_goal; 00116 static_map_goal.cloud_source = "full_cloud_filtered"; 00117 static_map_goal.number_of_clouds = 2; 00118 00119 make_static_collision_map_client_.sendGoal(static_map_goal); 00120 if(!setLaserScan(false)) 00121 { 00122 ROS_ERROR("Could not take laser scan"); 00123 return false; 00124 } 00125 if ( !make_static_collision_map_client_.waitForResult(ros::Duration(30.0)) ) 00126 { 00127 ROS_ERROR("Collision map was not formed in allowed time"); 00128 return false; 00129 } 00130 if(make_static_collision_map_client_.getState() != actionlib::SimpleClientGoalState::SUCCEEDED) 00131 { 00132 ROS_ERROR("Some non-success state was reached for static collision map. Proceed with caution"); 00133 return false; 00134 } 00135 ROS_INFO("Successful taking static map"); 00136 ros::Duration(1.0).sleep(); 00137 return true; 00138 } 00139 00140 private: 00142 ros::NodeHandle root_nh_; 00144 ros::ServiceClient tilt_laser_service_; 00145 00146 // Parameters for slow laser movement (high-res scanning) 00147 double laser_slow_period_; 00148 double laser_slow_amplitude_; 00149 double laser_slow_offset_; 00150 00151 // Parameters for fast lsaer movement (low-res scanning) 00152 double laser_fast_period_; 00153 double laser_fast_amplitude_; 00154 double laser_fast_offset_; 00155 00157 actionlib::SimpleActionClient<arm_navigation_msgs::MakeStaticCollisionMapAction> 00158 make_static_collision_map_client_; 00159 }; 00160 00161 }