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
00033
00034
00035
00036
00037 #include "pr2_plugs_actions/move_base_omnidirectional.h"
00038
00039 using namespace ros;
00040 using namespace std;
00041
00042 static const string fixed_frame = "odom_combined";
00043
00044 namespace pr2_plugs_actions{
00045
00046 MoveBaseOmnidirectionalAction::MoveBaseOmnidirectionalAction() :
00047 costmap_ros_("costmap_move_base", tf_),
00048 costmap_model_(costmap_),
00049 action_server_(ros::NodeHandle(),
00050 "move_base_omnidirectional",
00051 boost::bind(&MoveBaseOmnidirectionalAction::execute, this, _1))
00052 {
00053 costmap_ros_.stop();
00054
00055 ros::NodeHandle node_private("~");
00056 node_private.param("k_trans", K_trans, 1.0);
00057 node_private.param("k_rot", K_rot, 1.0);
00058 node_private.param("tolerance_trans", tolerance_trans, 0.02);
00059 node_private.param("tolerance_rot", tolerance_rot, 0.04);
00060
00061 ros::NodeHandle node;
00062 base_pub_ = node.advertise<geometry_msgs::Twist>("base_controller/command", 10);
00063
00064 footprint_ = costmap_ros_.getRobotFootprint();
00065 };
00066
00067
00068
00069 MoveBaseOmnidirectionalAction::~MoveBaseOmnidirectionalAction()
00070 {};
00071
00072
00073
00074 void MoveBaseOmnidirectionalAction::execute(const move_base_msgs::MoveBaseGoalConstPtr& goal)
00075 {
00076 ROS_INFO("MoveBaseOmnidirectionalAction: execute");
00077 costmap_ros_.start();
00078
00079
00080 tf::Stamped<tf::Pose> robot_pose;
00081 costmap_ros_.getRobotPose(robot_pose);
00082 ROS_INFO("MoveBaseOmnidirectionalAction: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(), tf::getYaw(robot_pose.getRotation()));
00083
00084
00085 tf::Stamped<tf::Pose> desired_pose;
00086 tf::poseStampedMsgToTF(goal->target_pose, desired_pose);
00087 if (!tf_.waitForTransform(fixed_frame, desired_pose.frame_id_, desired_pose.stamp_, ros::Duration(2.0))){
00088 ROS_ERROR("MoveBaseOmnidirectionalAction: could not transform from %s to %s", fixed_frame.c_str(), desired_pose.frame_id_.c_str());
00089 action_server_.setAborted();
00090 return;
00091 }
00092 tf_.transformPose(fixed_frame, desired_pose, desired_pose);
00093 ROS_INFO("MoveBaseOmnidirectionalAction: desired robot pose %f %f ==> %f", desired_pose.getOrigin().x(), desired_pose.getOrigin().y(), tf::getYaw(desired_pose.getRotation()));
00094
00095
00096 geometry_msgs::Twist diff = diff2D(desired_pose, robot_pose);
00097 ROS_INFO("MoveBaseOmnidirectionalAction: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
00098 ROS_INFO("MoveBaseOmnidirectionalAction: diff limit %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
00099 ros::Time goal_reached_time = ros::Time::now();
00100 while (goal_reached_time + ros::Duration(0.5) > ros::Time::now()) {
00101 diff = diff2D(desired_pose, robot_pose);
00102 ROS_DEBUG("Angular error: %f", fabs(diff.angular.z));
00103
00104 if (fabs(diff.linear.x) > tolerance_trans || fabs(diff.linear.y) > tolerance_trans || fabs(diff.angular.z) > tolerance_rot)
00105 goal_reached_time = ros::Time::now();
00106
00107 if (action_server_.isPreemptRequested()){
00108 ROS_WARN("MoveBaseOmnidirectionalAction: Preempted");
00109 lockWheels();
00110 action_server_.setPreempted();
00111 return;
00112 }
00113 base_pub_.publish(limitTwist(diff));
00114 costmap_ros_.getRobotPose(robot_pose);
00115 ros::Duration(0.01).sleep();
00116 }
00117 costmap_ros_.stop();
00118 lockWheels();
00119 action_server_.setSucceeded();
00120 }
00121
00122
00123
00124 void MoveBaseOmnidirectionalAction::lockWheels()
00125 {
00126 ROS_INFO("MoveBaseOmnidirectionalAction: Locking wheels sideways");
00127 geometry_msgs::Twist twist;
00128 twist.linear.y = -0.001;
00129 base_pub_.publish(twist);
00130 ros::Duration(0.5).sleep();
00131 twist.linear.y = 0.0;
00132 base_pub_.publish(twist);
00133 }
00134
00135 geometry_msgs::Twist MoveBaseOmnidirectionalAction::diff2D(const tf::Pose& pose1, const tf::Pose& pose2)
00136 {
00137 geometry_msgs::Twist res;
00138 tf::Pose diff = pose2.inverse() * pose1;
00139 res.linear.x = diff.getOrigin().x();
00140 res.linear.y = diff.getOrigin().y();
00141 res.angular.z = tf::getYaw(diff.getRotation());
00142 return res;
00143 }
00144
00145
00146 geometry_msgs::Twist MoveBaseOmnidirectionalAction::limitTwist(const geometry_msgs::Twist& twist)
00147 {
00148 geometry_msgs::Twist res = twist;
00149 res.linear.x *= K_trans;
00150 res.linear.y *= K_trans;
00151 res.angular.z *= K_rot;
00152
00153 if (fabs(res.linear.x) > 0.1) res.linear.x = 0.1 * res.linear.x / fabs(res.linear.x);
00154 if (fabs(res.linear.y) > 0.1) res.linear.y = 0.1 * res.linear.y / fabs(res.linear.y);
00155 if (fabs(res.angular.z) > 0.2) res.angular.z = 0.2 * res.angular.z / fabs(res.angular.z);
00156
00157 ROS_DEBUG("Angular command %f", res.angular.z);
00158 return res;
00159 }
00160
00161
00162
00163 std::vector<geometry_msgs::Point> MoveBaseOmnidirectionalAction::getOrientedFootprint(const tf::Vector3 pos, double theta_cost)
00164 {
00165 double cos_th = cos(theta_cost);
00166 double sin_th = sin(theta_cost);
00167 std::vector<geometry_msgs::Point> oriented_footprint;
00168 for(unsigned int i = 0; i < footprint_.size(); ++i){
00169 geometry_msgs::Point new_pt;
00170 new_pt.x = pos.x() + (footprint_[i].x * cos_th - footprint_[i].y * sin_th);
00171 new_pt.y = pos.y() + (footprint_[i].x * sin_th + footprint_[i].y * cos_th);
00172 oriented_footprint.push_back(new_pt);
00173 }
00174 return oriented_footprint;
00175 }
00176
00177
00178 }
00179
00180
00181
00182 int main(int argc, char** argv)
00183 {
00184 ros::init(argc, argv, "move_base_omnidirectional");
00185
00186 pr2_plugs_actions::MoveBaseOmnidirectionalAction action_server;
00187
00188 ros::spin();
00189 return 0;
00190 }