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
00038 #include <twist_recovery/twist_recovery.h>
00039 #include <pluginlib/class_list_macros.hpp>
00040 #include <tf/transform_datatypes.h>
00041
00042
00043 PLUGINLIB_EXPORT_CLASS(twist_recovery::TwistRecovery, nav_core::RecoveryBehavior)
00044
00045 namespace gm=geometry_msgs;
00046 namespace cmap=costmap_2d;
00047 namespace blp=base_local_planner;
00048 using std::vector;
00049 using std::max;
00050
00051 namespace twist_recovery
00052 {
00053
00054 TwistRecovery::TwistRecovery () :
00055 global_costmap_(NULL), local_costmap_(NULL), tf_(NULL), initialized_(false)
00056 {}
00057
00058 TwistRecovery::~TwistRecovery ()
00059 {
00060 delete world_model_;
00061 }
00062
00063 void TwistRecovery::initialize (std::string name, tf::TransformListener* tf,
00064 cmap::Costmap2DROS* global_cmap, cmap::Costmap2DROS* local_cmap)
00065 {
00066 ROS_ASSERT(!initialized_);
00067 name_ = name;
00068 tf_ = tf;
00069 local_costmap_ = local_cmap;
00070 global_costmap_ = global_cmap;
00071 world_model_ = new blp::CostmapModel(*local_costmap_->getCostmap());
00072
00073 pub_ = nh_.advertise<gm::Twist>("cmd_vel", 10);
00074 ros::NodeHandle private_nh("~/" + name);
00075
00076 {
00077 bool found=true;
00078 found = found && private_nh.getParam("linear_x", base_frame_twist_.linear.x);
00079 found = found && private_nh.getParam("linear_y", base_frame_twist_.linear.y);
00080 found = found && private_nh.getParam("angular_z", base_frame_twist_.angular.z);
00081 if (!found) {
00082 ROS_FATAL_STREAM ("Didn't find twist parameters in " << private_nh.getNamespace());
00083 ros::shutdown();
00084 }
00085 }
00086
00087 private_nh.param("duration", duration_, 1.0);
00088 private_nh.param("linear_speed_limit", linear_speed_limit_, 0.3);
00089 private_nh.param("angular_speed_limit", angular_speed_limit_, 1.0);
00090 private_nh.param("linear_acceleration_limit", linear_acceleration_limit_, 4.0);
00091 private_nh.param("angular_acceleration_limit", angular_acceleration_limit_, 3.2);
00092 private_nh.param("controller_frequency", controller_frequency_, 20.0);
00093 private_nh.param("simulation_inc", simulation_inc_, 1/controller_frequency_);
00094
00095 ROS_INFO_STREAM_NAMED ("top", "Initialized twist recovery with twist " <<
00096 base_frame_twist_ << " and duration " << duration_);
00097
00098 initialized_ = true;
00099 }
00100
00101 gm::Twist scaleTwist (const gm::Twist& twist, const double scale)
00102 {
00103 gm::Twist t;
00104 t.linear.x = twist.linear.x * scale;
00105 t.linear.y = twist.linear.y * scale;
00106 t.angular.z = twist.angular.z * scale;
00107 return t;
00108 }
00109
00110 gm::Pose2D forwardSimulate (const gm::Pose2D& p, const gm::Twist& twist, const double t=1.0)
00111 {
00112 gm::Pose2D p2;
00113 p2.x = p.x + twist.linear.x*t;
00114 p2.y = p.y + twist.linear.y*t;
00115 p2.theta = p.theta + twist.angular.z*t;
00116 return p2;
00117 }
00118
00120 double TwistRecovery::normalizedPoseCost (const gm::Pose2D& pose) const
00121 {
00122 const double c = world_model_->footprintCost(pose.x, pose.y, pose.theta, local_costmap_->getRobotFootprint(), 0.0, 0.0);
00123 return c < 0 ? 1e9 : c;
00124 }
00125
00126
00131 double TwistRecovery::nonincreasingCostInterval (const gm::Pose2D& current, const gm::Twist& twist) const
00132 {
00133 double cost = normalizedPoseCost(current);
00134 double t;
00135 for (t=simulation_inc_; t<=duration_; t+=simulation_inc_) {
00136 const double next_cost = normalizedPoseCost(forwardSimulate(current, twist, t));
00137 if (next_cost > cost) {
00138 ROS_DEBUG_STREAM_NAMED ("cost", "Cost at " << t << " and pose " << forwardSimulate(current, twist, t)
00139 << " is " << next_cost << " which is greater than previous cost " << cost);
00140 break;
00141 }
00142 cost = next_cost;
00143 }
00144
00145 return t-simulation_inc_;
00146 }
00147
00148 double linearSpeed (const gm::Twist& twist)
00149 {
00150 return sqrt(twist.linear.x*twist.linear.x + twist.linear.y*twist.linear.y);
00151 }
00152
00153 double angularSpeed (const gm::Twist& twist)
00154 {
00155 return fabs(twist.angular.z);
00156 }
00157
00158
00159 gm::Twist TwistRecovery::scaleGivenAccelerationLimits (const gm::Twist& twist, const double time_remaining) const
00160 {
00161 const double linear_speed = linearSpeed(twist);
00162 const double angular_speed = angularSpeed(twist);
00163 const double linear_acc_scaling = linear_speed/(time_remaining*linear_acceleration_limit_);
00164 const double angular_acc_scaling = angular_speed/(time_remaining*angular_acceleration_limit_);
00165 const double acc_scaling = max(linear_acc_scaling, angular_acc_scaling);
00166 const double linear_vel_scaling = linear_speed/linear_speed_limit_;
00167 const double angular_vel_scaling = angular_speed/angular_speed_limit_;
00168 const double vel_scaling = max(linear_vel_scaling, angular_vel_scaling);
00169 return scaleTwist(twist, max(1.0, max(acc_scaling, vel_scaling)));
00170 }
00171
00172
00173 gm::Pose2D TwistRecovery::getCurrentLocalPose () const
00174 {
00175 tf::Stamped<tf::Pose> p;
00176 local_costmap_->getRobotPose(p);
00177 gm::Pose2D pose;
00178 pose.x = p.getOrigin().x();
00179 pose.y = p.getOrigin().y();
00180 pose.theta = tf::getYaw(p.getRotation());
00181 return pose;
00182 }
00183
00184 void TwistRecovery::runBehavior ()
00185 {
00186 ROS_ASSERT (initialized_);
00187
00188
00189 const gm::Pose2D& current = getCurrentLocalPose();
00190
00191 const double d = nonincreasingCostInterval(current, base_frame_twist_);
00192 ros::Rate r(controller_frequency_);
00193 ROS_INFO_NAMED ("top", "Applying (%.2f, %.2f, %.2f) for %.2f seconds", base_frame_twist_.linear.x,
00194 base_frame_twist_.linear.y, base_frame_twist_.angular.z, d);
00195
00196
00197 for (double t=0; t<d; t+=1/controller_frequency_) {
00198 pub_.publish(scaleGivenAccelerationLimits(base_frame_twist_, d-t));
00199 r.sleep();
00200 }
00201 }
00202
00203
00204 }
00205