00001 #include <robot_operator/RobotOperator.h>
00002 #include <nav_msgs/GridCells.h>
00003
00004 #include <math.h>
00005
00006 #define PI 3.14159265
00007
00008 RobotOperator::RobotOperator(NodeHandle* n)
00009 {
00010
00011 mLocalMap = new Costmap2DROS("local_map", mTfListener);
00012 mRasterSize = mLocalMap->getCostmap()->getResolution();
00013
00014
00015 mCommandSubscriber = n->subscribe(COMMAND_TOPIC, 1, &RobotOperator::receiveCommand, this);
00016 mControlPublisher = n->advertise<geometry_msgs::Twist>(CONTROL_TOPIC, 1);
00017 mCostPublisher = n->advertise<geometry_msgs::Vector3>("costs", 1);
00018
00019
00020 NodeHandle operatorNode("~/");
00021 operatorNode.param("publish_route", mPublishRoute, false);
00022 if(mPublishRoute)
00023 {
00024 ROS_INFO("Will publish desired direction on '%s' and control direction on '%s'.", ROUTE_TOPIC, PLAN_TOPIC);
00025 mTrajectoryPublisher = n->advertise<nav_msgs::GridCells>(ROUTE_TOPIC, 1);
00026 mPlanPublisher = n->advertise<nav_msgs::GridCells>(PLAN_TOPIC, 1);
00027 }
00028 operatorNode.param("max_free_space", mMaxFreeSpace, 5.0);
00029 operatorNode.param("safety_decay", mSafetyDecay, 0.95);
00030 operatorNode.param("distance_weight", mDistanceWeight, 1);
00031 operatorNode.param("safety_weight", mSafetyWeight, 1);
00032 operatorNode.param("conformance_weight", mConformanceWeight, 1);
00033 operatorNode.param("continue_weight", mContinueWeight, 1);
00034 operatorNode.param("max_velocity", mMaxVelocity, 1.0);
00035
00036 ros::NodeHandle robotNode;
00037 robotNode.param("robot_frame", mRobotFrame, std::string("robot"));
00038 robotNode.param("odometry_frame", mOdometryFrame, std::string("odometry_base"));
00039
00040
00041 std::string tfPrefix = mTfListener.getTFPrefix();
00042 mRobotFrame = tf::resolve(tfPrefix, mRobotFrame);
00043 mOdometryFrame = tf::resolve(tfPrefix, mOdometryFrame);
00044
00045
00046 ROS_INFO("Initializing LUT...");
00047 initTrajTable();
00048 ROS_INFO("...done!");
00049
00050
00051 mDesiredDirection = 0;
00052 mDesiredVelocity = 0;
00053 mCurrentDirection = 0;
00054 mCurrentVelocity = 0;
00055 mDriveMode = 0;
00056 mRecoverySteps = 0;
00057 }
00058
00059 RobotOperator::~RobotOperator()
00060 {
00061 delete mLocalMap;
00062 for(int i = 0; i < LUT_RESOLUTION; i++)
00063 {
00064 delete mTrajTable[i];
00065 }
00066 }
00067
00068 void RobotOperator::initTrajTable()
00069 {
00070 for(int i = 0; i < (LUT_RESOLUTION * 4) + 2; i++)
00071 {
00072 mTrajTable[i] = NULL;
00073 }
00074 for(int i = 1; i < LUT_RESOLUTION; i++)
00075 {
00076 double tw = -PI * i / LUT_RESOLUTION;
00077 double tx = cos(tw) + 1;
00078 double ty = -sin(tw);
00079 double tr = ((tx*tx)+(ty*ty))/(ty+ty);
00080 std::vector<geometry_msgs::Point32> points;
00081 double alpha = 0;
00082 while(alpha < PI)
00083 {
00084 double x = tr * sin(alpha);
00085 double y = tr * (1.0 - cos(alpha));
00086 geometry_msgs::Point32 p;
00087 p.x = x;
00088 p.y = y;
00089 p.z = 0;
00090 points.push_back(p);
00091 alpha += mRasterSize / tr;
00092 }
00093
00094
00095 sensor_msgs::PointCloud* flcloud = new sensor_msgs::PointCloud();
00096 flcloud->header.stamp = Time(0);
00097 flcloud->header.frame_id = mRobotFrame;
00098 flcloud->points.resize(points.size());
00099
00100
00101 sensor_msgs::PointCloud* frcloud = new sensor_msgs::PointCloud();
00102 frcloud->header.stamp = Time(0);
00103 frcloud->header.frame_id = mRobotFrame;
00104 frcloud->points.resize(points.size());
00105
00106
00107 sensor_msgs::PointCloud* blcloud = new sensor_msgs::PointCloud();
00108 blcloud->header.stamp = Time(0);
00109 blcloud->header.frame_id = mRobotFrame;
00110 blcloud->points.resize(points.size());
00111
00112
00113 sensor_msgs::PointCloud* brcloud = new sensor_msgs::PointCloud();
00114 brcloud->header.stamp = Time(0);
00115 brcloud->header.frame_id = mRobotFrame;
00116 brcloud->points.resize(points.size());
00117
00118 for(unsigned int j = 0; j < points.size(); j++)
00119 {
00120 flcloud->points[j] = points[j];
00121 frcloud->points[j] = points[j];
00122 blcloud->points[j] = points[j];
00123 brcloud->points[j] = points[j];
00124
00125 frcloud->points[j].y *= -1;
00126 blcloud->points[j].x *= -1;
00127 brcloud->points[j].x *= -1;
00128 brcloud->points[j].y *= -1;
00129 }
00130 mTrajTable[LUT_RESOLUTION - i] = flcloud;
00131 mTrajTable[LUT_RESOLUTION + i] = frcloud;
00132 mTrajTable[(3 * LUT_RESOLUTION + 1) - i] = blcloud;
00133 mTrajTable[(3 * LUT_RESOLUTION + 1) + i] = brcloud;
00134 }
00135
00136
00137 geometry_msgs::Point32 p;
00138 p.x = 0;
00139 p.y = 0;
00140 p.z = 0;
00141
00142 sensor_msgs::PointCloud* turn = new sensor_msgs::PointCloud();
00143 turn->header.stamp = Time(0);
00144 turn->header.frame_id = mRobotFrame;
00145 turn->points.resize(1);
00146 turn->points[0] = p;
00147
00148 int straight_len = 5.0 / mRasterSize;
00149
00150 sensor_msgs::PointCloud* fscloud = new sensor_msgs::PointCloud();
00151 fscloud->header.stamp = Time(0);
00152 fscloud->header.frame_id = mRobotFrame;
00153 fscloud->points.resize(straight_len);
00154
00155 sensor_msgs::PointCloud* bscloud = new sensor_msgs::PointCloud();
00156 bscloud->header.stamp = Time(0);
00157 bscloud->header.frame_id = mRobotFrame;
00158 bscloud->points.resize(straight_len);
00159
00160 for(int i = 0; i < straight_len; i++)
00161 {
00162 fscloud->points[i] = p;
00163 bscloud->points[i] = p;
00164 bscloud->points[i].x *= -1;
00165 p.x += mRasterSize;
00166 }
00167
00168 mTrajTable[LUT_RESOLUTION] = fscloud;
00169 mTrajTable[LUT_RESOLUTION*3 + 1] = bscloud;
00170
00171 mTrajTable[0] = turn;
00172 mTrajTable[LUT_RESOLUTION*2] = turn;
00173 mTrajTable[LUT_RESOLUTION*2 + 1] = turn;
00174 mTrajTable[LUT_RESOLUTION*4 + 1] = turn;
00175
00176 for(int i = 0; i < (LUT_RESOLUTION * 4) + 2; i++)
00177 {
00178 if(!mTrajTable[i])
00179 {
00180 ROS_ERROR("Table entry %d has not been initialized!", i);
00181 }
00182 }
00183 }
00184
00185 void RobotOperator::receiveCommand(const robot_operator::cmd::ConstPtr& msg)
00186 {
00187 if(msg->Turn < -1 || msg->Turn > 1)
00188 {
00189
00190
00191 mDesiredDirection = 0;
00192 mDesiredVelocity = 0;
00193 mCurrentDirection = 0;
00194 mCurrentVelocity = 0;
00195 ROS_ERROR("Invalid turn direction on topic '%s'!", COMMAND_TOPIC);
00196 return;
00197 }
00198 mDesiredDirection = msg->Turn;
00199 mDesiredVelocity = msg->Velocity * mMaxVelocity;
00200 mDriveMode = msg->Mode;
00201 }
00202
00203 void RobotOperator::executeCommand()
00204 {
00205
00206 mCostmap = mLocalMap->getCostmap();
00207 double bestDirection, d;
00208
00209
00210 switch(mDriveMode)
00211 {
00212 case 0:
00213
00214 bestDirection = findBestDirection();
00215 d = bestDirection - mCurrentDirection;
00216 if(d < -0.2) d = -0.2;
00217 if(d > 0.2) d = 0.2;
00218 mCurrentDirection += d;
00219 mCurrentVelocity = mDesiredVelocity;
00220 break;
00221 case 1:
00222 mCurrentDirection = mDesiredDirection;
00223 mCurrentVelocity = mDesiredVelocity;
00224 break;
00225 default:
00226 ROS_ERROR("Invalid drive mode!");
00227 mCurrentVelocity = 0.0;
00228 }
00229
00230
00231 evaluateAction(mCurrentDirection, mCurrentVelocity, true);
00232
00233 sensor_msgs::PointCloud* originalCloud = getPointCloud(mCurrentDirection, mDesiredVelocity);
00234 sensor_msgs::PointCloud transformedCloud;
00235
00236 try
00237 {
00238 mTfListener.transformPointCloud(mOdometryFrame,*originalCloud,transformedCloud);
00239 }
00240 catch(TransformException ex)
00241 {
00242 ROS_ERROR("%s", ex.what());
00243 return;
00244 }
00245
00246
00247 int freeCells = calculateFreeSpace(&transformedCloud);
00248 double freeSpace = mRasterSize * freeCells;
00249
00250 double safeVelocity = (freeSpace / mMaxFreeSpace) + 0.05;
00251 if(freeCells == transformedCloud.points.size() && safeVelocity < 0.5)
00252 safeVelocity = 0.5;
00253
00254 if(freeSpace < 0.3 && freeCells < transformedCloud.points.size())
00255 safeVelocity = 0;
00256
00257 if(safeVelocity > mMaxVelocity)
00258 safeVelocity = mMaxVelocity;
00259
00260
00261 if(mRecoverySteps > 0) mRecoverySteps--;
00262 if(safeVelocity < 0.1)
00263 {
00264 if(mDriveMode == 0)
00265 {
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276 mRecoverySteps = 30;
00277 ROS_WARN_THROTTLE(1, "Robot is stuck! Trying to recover...");
00278 }else
00279 {
00280 mCurrentVelocity = 0;
00281 ROS_WARN_THROTTLE(1, "Robot cannot move further in this direction!");
00282 }
00283 }
00284
00285
00286 if(mPublishRoute)
00287 {
00288 nav_msgs::GridCells route_msg;
00289 route_msg.header.frame_id = mOdometryFrame;
00290 route_msg.header.stamp = Time::now();
00291
00292 route_msg.cell_width = mCostmap->getResolution();
00293 route_msg.cell_height = mCostmap->getResolution();
00294
00295 route_msg.cells.resize(freeCells);
00296 for(int i = 0; i < freeCells; i++)
00297 {
00298 route_msg.cells[i].x = transformedCloud.points[i].x;
00299 route_msg.cells[i].y = transformedCloud.points[i].y;
00300 route_msg.cells[i].z = transformedCloud.points[i].z;
00301 }
00302 mTrajectoryPublisher.publish(route_msg);
00303
00304
00305 sensor_msgs::PointCloud* originalPlanCloud = getPointCloud(mDesiredDirection, mDesiredVelocity);
00306 sensor_msgs::PointCloud transformedPlanCloud;
00307
00308 try
00309 {
00310 mTfListener.transformPointCloud(mOdometryFrame,*originalPlanCloud,transformedPlanCloud);
00311 }
00312 catch(TransformException ex)
00313 {
00314 ROS_ERROR("%s", ex.what());
00315 return;
00316 }
00317 nav_msgs::GridCells plan_msg;
00318 plan_msg.header = route_msg.header;
00319
00320 plan_msg.cell_width = mCostmap->getResolution();
00321 plan_msg.cell_height = mCostmap->getResolution();
00322
00323 int freeSpacePlan = calculateFreeSpace(&transformedPlanCloud);
00324 plan_msg.cells.resize(freeSpacePlan);
00325 for(int i = 0; i < freeSpacePlan; i++)
00326 {
00327 plan_msg.cells[i].x = transformedPlanCloud.points[i].x;
00328 plan_msg.cells[i].y = transformedPlanCloud.points[i].y;
00329 plan_msg.cells[i].z = transformedPlanCloud.points[i].z;
00330 }
00331 mPlanPublisher.publish(plan_msg);
00332 }
00333
00334
00335 geometry_msgs::Twist controlMsg;
00336 double velocity = mCurrentVelocity;
00337 if(mCurrentDirection == 0)
00338 {
00339 if(velocity > safeVelocity)
00340 {
00341 ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, safeVelocity);
00342 velocity = safeVelocity;
00343 }else if(velocity < -safeVelocity)
00344 {
00345 ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, -safeVelocity);
00346 velocity = -safeVelocity;
00347 }
00348 controlMsg.linear.x = velocity;
00349 controlMsg.angular.z = 0;
00350 }else if(mCurrentDirection == -1 || mCurrentDirection == 1)
00351 {
00352 controlMsg.linear.x = 0;
00353 controlMsg.angular.z = -1.0 * mCurrentDirection * velocity;
00354 }else
00355 {
00356 double x = sin(mCurrentDirection * PI);
00357 double y = (cos(mCurrentDirection * PI) + 1);
00358 double r = ((x*x) + (y*y)) / (2*x);
00359 double abs_r = (r > 0) ? r : -r;
00360 velocity /= (1 + (1.0/abs_r));
00361 if(velocity > safeVelocity)
00362 {
00363 ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, safeVelocity);
00364 velocity = safeVelocity;
00365 }else if(velocity < -safeVelocity)
00366 {
00367 ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, -safeVelocity);
00368 velocity = -safeVelocity;
00369 }
00370
00371 controlMsg.linear.x = velocity;
00372 controlMsg.angular.z = -1.0 / r * controlMsg.linear.x;
00373 }
00374 mControlPublisher.publish(controlMsg);
00375 }
00376
00377 int RobotOperator::calculateFreeSpace(sensor_msgs::PointCloud* cloud)
00378 {
00379 unsigned int mx, my;
00380 int length = cloud->points.size();
00381 int freeSpace = 0;
00382 for(int i = 0; i < length; i++)
00383 {
00384 if(mCostmap->worldToMap(cloud->points[i].x, cloud->points[i].y, mx, my))
00385 {
00386 if(mCostmap->getCost(mx,my) < INSCRIBED_INFLATED_OBSTACLE)
00387 {
00388 freeSpace++;
00389 }else
00390 {
00391 break;
00392 }
00393 }else
00394 {
00395 break;
00396 }
00397 }
00398 return freeSpace;
00399 }
00400
00401 double RobotOperator::evaluateAction(double direction, double velocity, bool debug)
00402 {
00403 sensor_msgs::PointCloud* originalCloud = getPointCloud(direction, velocity);
00404 sensor_msgs::PointCloud transformedCloud;
00405 try
00406 {
00407 mTfListener.transformPointCloud(mOdometryFrame, *originalCloud,transformedCloud);
00408 }
00409 catch(TransformException ex)
00410 {
00411 ROS_ERROR("%s", ex.what());
00412 return 1;
00413 }
00414
00415 double valueDistance = 0.0;
00416 double valueSafety = 0.0;
00417 double valueConformance = 0.0;
00418
00419 double freeSpace = 0.0;
00420 double decay = 1.0;
00421 unsigned char cell_cost;
00422 double safety;
00423
00424
00425 int length = transformedCloud.points.size();
00426 bool gettingBetter = true;
00427 for(int i = 0; i < length; i++)
00428 {
00429 unsigned int mx, my;
00430 if(mCostmap->worldToMap(transformedCloud.points[i].x, transformedCloud.points[i].y, mx, my))
00431 {
00432 cell_cost = mCostmap->getCost(mx,my);
00433 if(cell_cost >= INSCRIBED_INFLATED_OBSTACLE)
00434 {
00435
00436 break;
00437 }
00438 }
00439 freeSpace += mRasterSize;
00440
00441 safety = INSCRIBED_INFLATED_OBSTACLE - (cell_cost * decay);
00442 if(gettingBetter)
00443 {
00444 if(safety >= valueSafety) valueSafety = safety;
00445 else gettingBetter = false;
00446 }else
00447 {
00448 if(safety < valueSafety) valueSafety = safety;
00449 }
00450 decay *= mSafetyDecay;
00451 }
00452
00453 double action_value = 0.0;
00454 double normFactor = 0.0;
00455 valueSafety /= INSCRIBED_INFLATED_OBSTACLE;
00456
00457
00458 if(freeSpace >= mMaxFreeSpace)
00459 {
00460 freeSpace = mMaxFreeSpace;
00461 }
00462 valueDistance = freeSpace / std::min(mMaxFreeSpace, length*mRasterSize);
00463 normFactor = mDistanceWeight + mSafetyWeight;
00464
00465 if(mRecoverySteps == 0)
00466 {
00467
00468 double valueContinue = mCurrentDirection - direction;
00469 if(valueContinue < 0) valueContinue *= -1;
00470 valueContinue = 1.0 / (1.0 + exp(pow(valueContinue-0.5,15)));
00471
00472
00473 double desired_sq = (mDesiredDirection > 0) ? mDesiredDirection * mDesiredDirection : mDesiredDirection * -mDesiredDirection;
00474 double evaluated_sq = (direction > 0) ? direction * direction : direction * -direction;
00475 valueConformance = cos(PI / 2.0 * (desired_sq - evaluated_sq));
00476
00477 action_value += valueConformance * mConformanceWeight;
00478 action_value += valueContinue * mContinueWeight;
00479 normFactor += mConformanceWeight + mContinueWeight;
00480 }
00481
00482 action_value += valueDistance * mDistanceWeight;
00483 action_value += valueSafety * mSafetyWeight;
00484 action_value /= normFactor;
00485
00486 if(debug)
00487 {
00488 geometry_msgs::Vector3 cost_msg;
00489 cost_msg.x = valueDistance;
00490 cost_msg.y = valueSafety;
00491
00492 cost_msg.z = valueConformance;
00493 mCostPublisher.publish(cost_msg);
00494 }
00495
00496 return action_value;
00497 }
00498
00499 double diff(double v1, double v2)
00500 {
00501 if(v1 > v2)
00502 return v1 - v2;
00503 else
00504 return v2 - v1;
00505 }
00506
00507 double RobotOperator::findBestDirection()
00508 {
00509 double best_dir = -1.0;
00510 double best_value = 0.0;
00511 double step = 0.01;
00512 double dir = -1.0;
00513
00514 while(dir <= 1.0)
00515 {
00516 double value = evaluateAction(dir, mDesiredVelocity);
00517 if(value > best_value)
00518 {
00519 best_dir = dir;
00520 best_value = value;
00521 }
00522 dir += step;
00523 }
00524
00525
00526
00527
00528
00529
00530
00531 return best_dir;
00532 }
00533
00534 sensor_msgs::PointCloud* RobotOperator::getPointCloud(double direction, double velocity)
00535 {
00536 if(direction < -1) direction = -1;
00537 if(direction > 1) direction = 1;
00538 int offset = (velocity >= 0) ? LUT_RESOLUTION : 3*LUT_RESOLUTION + 1;
00539 int table_index = (direction * LUT_RESOLUTION) + offset;
00540 return mTrajTable[table_index];
00541 }