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