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 <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
00050 if(!tfl_)
00051 {
00052 tfl_ = new tf::TransformListener();
00053 delete_tfl_ = true;
00054 }
00055
00056
00057 cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("base_controller/command", 1);
00058
00059
00060 pose_estimate_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("/initialpose", 1);
00061
00062
00063 sub_nav_status_ = nh_.subscribe<actionlib_msgs::GoalStatusArray>("move_base/status", 10,
00064 boost::bind(&BaseClient::moveBaseStatusCB, this, _1));
00065
00066
00067 sub_nav_result_ = nh_.subscribe<move_base_msgs::MoveBaseActionResult>("move_base/result", 10,
00068 boost::bind(&BaseClient::moveBaseResultCB, this, _1));
00069
00070
00071 publish_timer_ = nh_.createTimer(ros::Duration(0.05), boost::bind(&BaseClient::publishTwist, this, _1));
00072 }
00073
00074 BaseClient::~BaseClient(){
00075 if(delete_tfl_)
00076 delete tfl_;
00077 }
00078
00080 bool BaseClient::hasGoal()
00081 {
00082 return move_base_active_;
00083 }
00084
00086
00087
00088
00089
00090
00091
00093 void BaseClient::cancelGoals()
00094 {
00095 ROS_INFO("Canceling all move_base goals!");
00096 move_base_client_.client().cancelAllGoals();
00097 }
00098
00100 void BaseClient::moveBaseResultCB( const move_base_msgs::MoveBaseActionResultConstPtr &result)
00101 {
00102 if(result->status.status == result->status.SUCCEEDED)
00103 {
00104 ROS_INFO("Move base reports succeeded, text: %s", result->status.text.c_str());
00105 }
00106 else if(result->status.status == result->status.PREEMPTED)
00107 {
00108 ROS_INFO("Move base reports preempted, text: %s", result->status.text.c_str());
00109 }
00110 else if(result->status.status == result->status.ABORTED)
00111 {
00112 ROS_INFO("Move base reports aborted, text: %s", result->status.text.c_str());
00113 }
00114 else if(result->status.status == result->status.REJECTED)
00115 {
00116 ROS_INFO("Move base reports goal rejected, text: %s", result->status.text.c_str());
00117 }
00118 else
00119 {
00120 ROS_INFO("Move base result was %d, text: %s", result->status.status, result->status.text.c_str());
00121 }
00122 }
00123
00125 void BaseClient::moveBaseStatusCB( const actionlib_msgs::GoalStatusArrayConstPtr &array)
00126 {
00127 size_t num = array->status_list.size();
00128 bool is_active = false;
00129 for(size_t i = 0; i < num; i++)
00130 {
00131 actionlib_msgs::GoalStatus goal_status = array->status_list[i];
00132 if(goal_status.status == goal_status.ACTIVE || goal_status.status == goal_status.PENDING)
00133 {
00134 ROS_DEBUG("Got a move_base goal status that is active or pending!");
00135 is_active = true;
00136 }
00137 else
00138 {
00139 ROS_DEBUG("Base client for goal %zd got status update: %d", i, goal_status.status);
00140 }
00141 }
00142 move_base_active_ = is_active;
00143 }
00144
00146 void BaseClient::applyTwist(const geometry_msgs::TwistStamped &ts)
00147 {
00148
00149 base_cmd_ = ts;
00150 }
00151
00153 void BaseClient::publishTwist(const ros::TimerEvent &e)
00154 {
00155
00156 geometry_msgs::TwistStamped cmd = base_cmd_;
00157 if( ( (e.current_real - base_cmd_.header.stamp) > timeout_) )
00158 {
00159 cmd.twist.linear.x = cmd.twist.linear.y = cmd.twist.linear.z = 0.0;
00160 cmd.twist.angular.x = cmd.twist.angular.y = cmd.twist.angular.z = 0.0;
00161 }
00162
00163 tf::Vector3 linear;
00164 tf::Vector3 angular;
00165
00166 tf::vector3MsgToTF(cmd.twist.linear, linear);
00167 tf::vector3MsgToTF(cmd.twist.angular, angular);
00168
00169 float nu = 0.4;
00170
00171 last_linear_ = nu*linear + (1.0 -nu)*last_linear_;
00172 last_angular_ = nu*angular + (1.0 -nu)*last_angular_;
00173
00174
00175 if ( linear.length() == 0.0 && last_linear_.length() == 0 &&
00176 angular.length() == 0.0 && last_angular_.length() == 0 )
00177 {
00178 return;
00179 }
00180
00181 geometry_msgs::Twist newcmd;
00182 tf::vector3TFToMsg(last_linear_, newcmd.linear);
00183 tf::vector3TFToMsg(last_angular_, newcmd.angular);
00184 cmd_vel_pub_.publish(newcmd);
00185 }
00186
00187 void BaseClient::sendNavGoal( const geometry_msgs::PoseStamped &ps)
00188 {
00189 move_base_msgs::MoveBaseGoal goal;
00190 goal.target_pose = ps;
00191 ROS_DEBUG_STREAM("Sending move_base_goal \n" << ps);
00192
00193
00194 move_base_client_.client().sendGoal( goal );
00195 }
00196
00197 void BaseClient::sendPoseEstimate(const geometry_msgs::PoseWithCovarianceStamped &ps)
00198 {
00199 ROS_DEBUG_STREAM("Sending pose estimate. \n" << ps);
00200 pose_estimate_pub_.publish(ps);
00201 }
00202
00203 void BaseClient::clearLocalCostmap( )
00204 {
00205
00206
00207 std_srvs::Empty srv;
00208 if (!local_costmap_reset_srv_.client().call(srv)) ROS_ERROR("failed to call costmap reset client");
00209
00210 }
00211
00212 }