$search
00001 /* 00002 * Copyright (c) 2011, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 // author: Adam Leeper 00031 00032 #include <pr2_wrappers/base_client.h> 00033 00034 namespace pr2_wrappers { 00035 00036 00037 BaseClient::BaseClient(ros::NodeHandle &nh, const ros::Duration &timeout, tf::TransformListener *tfl) : 00038 delete_tfl_(false), 00039 move_base_client_("move_base", true), 00040 move_base_active_(false), 00041 last_linear_(0,0,0), 00042 last_angular_(0,0,0), 00043 timeout_(timeout), 00044 local_costmap_reset_srv_("/move_base/clear_costmaps") 00045 { 00046 nh_ = nh; 00047 tfl_ = tfl; 00048 00049 // Create a new tfl if we didn't receive a pointer to one, and mark it for deletion. 00050 if(!tfl_) 00051 { 00052 tfl_ = new tf::TransformListener(); 00053 delete_tfl_ = true; 00054 } 00055 00056 //set up the publisher for the cmd_vel topic 00057 cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("base_controller/command", 1); 00058 00059 // Subscribe to the status message for the move_base action server 00060 sub_nav_status_ = nh_.subscribe<actionlib_msgs::GoalStatusArray>("move_base/status", 10, boost::bind(&BaseClient::moveBaseStatusCB, this, _1)); 00061 00062 // Setup the timer callback for publishing updates 00063 publish_timer_ = nh_.createTimer(ros::Duration(0.05), boost::bind(&BaseClient::publishTwist, this, _1)); 00064 } 00065 00066 BaseClient::~BaseClient(){ 00067 if(delete_tfl_) 00068 delete tfl_; 00069 } 00070 00072 bool BaseClient::hasGoal() 00073 { 00074 return move_base_active_; 00075 } 00076 00078 //void BaseClient::queryGoalState() 00079 //{ 00080 // actionlib::SimpleClientGoalState state = move_base_client_.getState(); 00081 // move_base_active_ = ( state == state.ACTIVE || state == state.PENDING ); 00082 //} 00083 00085 void BaseClient::cancelGoals() 00086 { 00087 ROS_INFO("Canceling all move_base goals!"); 00088 move_base_client_.client().cancelAllGoals(); 00089 } 00090 00092 void BaseClient::moveBaseStatusCB( const actionlib_msgs::GoalStatusArrayConstPtr &array) 00093 { 00094 size_t num = array->status_list.size(); 00095 bool is_active = false; 00096 for(size_t i = 0; i < num; i++) 00097 { 00098 actionlib_msgs::GoalStatus goal_status = array->status_list[i]; 00099 if(goal_status.status == goal_status.ACTIVE || goal_status.status == goal_status.PENDING) 00100 { 00101 ROS_DEBUG("Got a move_base goal status that is active or pending!"); 00102 is_active = true; 00103 } 00104 //ROS_WARN("Base client got status update: %d", goal_status.status); 00105 } 00106 move_base_active_ = is_active; 00107 } 00108 00110 void BaseClient::applyTwist(const geometry_msgs::TwistStamped &ts) 00111 { 00112 //store the base command 00113 base_cmd_ = ts; 00114 } 00115 00117 void BaseClient::publishTwist(const ros::TimerEvent &e) 00118 { 00119 tf::Vector3 linear; 00120 tf::Vector3 angular; 00121 00122 tf::vector3MsgToTF(base_cmd_.twist.linear, linear); 00123 tf::vector3MsgToTF(base_cmd_.twist.angular, angular); 00124 00125 float nu = 0.4; 00126 00127 last_linear_ = nu*linear + (1.0 -nu)*last_linear_; 00128 last_angular_ = nu*angular + (1.0 -nu)*last_angular_; 00129 00130 geometry_msgs::Twist cmd; 00131 tf::vector3TFToMsg(last_linear_, cmd.linear); 00132 tf::vector3TFToMsg(last_angular_, cmd.angular); 00133 00134 // send the command if it isn't too old 00135 if( ( (e.current_real - base_cmd_.header.stamp) < timeout_) ) 00136 { 00137 //if( linear.length() > 0.01 || angular.length() > 0.01 ) 00138 // ROS_INFO("Publishing updated twist command to base."); 00139 cmd_vel_pub_.publish(cmd); 00140 } 00141 } 00142 00143 void BaseClient::sendNavGoal( const geometry_msgs::PoseStamped &ps) 00144 { 00145 move_base_msgs::MoveBaseGoal goal; 00146 goal.target_pose = ps; 00147 ROS_DEBUG_STREAM("Sending move_base_goal \n" << ps); 00148 // aleeper: I think we can just send the goal here and not wait for a result, because we already have 00149 // functionality above for monitoring the state of the nav stack. 00150 move_base_client_.client().sendGoal( goal ); //, boost::bind(&BaseClient::testGripperResultCallback, this, _1, _2)); 00151 00152 00153 } 00154 00155 void BaseClient::clearLocalCostmap( ) 00156 { 00157 00158 00159 std_srvs::Empty srv; 00160 if (!local_costmap_reset_srv_.client().call(srv)) ROS_ERROR("failed to call costmap reset client"); 00161 00162 } 00163 00164 } // namespace