00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include <stdr_robot/stdr_robot.h>
00023 #include <nodelet/NodeletUnload.h>
00024 #include <pluginlib/class_list_macros.h>
00025
00026 PLUGINLIB_EXPORT_CLASS(stdr_robot::Robot, nodelet::Nodelet)
00027
00028 namespace stdr_robot
00029 {
00034 Robot::Robot(void)
00035 {
00036
00037 }
00038
00043 void Robot::onInit()
00044 {
00045 ros::NodeHandle n = getMTNodeHandle();
00046
00047 _odomPublisher = n.advertise<nav_msgs::Odometry>(getName() + "/odom", 10);
00048
00049 _registerClientPtr.reset(
00050 new RegisterRobotClient(n, "stdr_server/register_robot", true) );
00051
00052 _registerClientPtr->waitForServer();
00053
00054 stdr_msgs::RegisterRobotGoal goal;
00055 goal.name = getName();
00056 _registerClientPtr->sendGoal(goal,
00057 boost::bind(&Robot::initializeRobot, this, _1, _2));
00058
00059 _mapSubscriber = n.subscribe("map", 1, &Robot::mapCallback, this);
00060 _moveRobotService = n.advertiseService(
00061 getName() + "/replace", &Robot::moveRobotCallback, this);
00062
00063
00064 _tfTimer = n.createTimer(
00065 ros::Duration(0.1), &Robot::publishTransforms, this, false, false);
00066 }
00067
00074 void Robot::initializeRobot(
00075 const actionlib::SimpleClientGoalState& state,
00076 const stdr_msgs::RegisterRobotResultConstPtr result)
00077 {
00078
00079 if (state == state.ABORTED) {
00080 NODELET_ERROR("Something really bad happened...");
00081 return;
00082 }
00083
00084 NODELET_INFO("Loaded new robot, %s", getName().c_str());
00085 ros::NodeHandle n = getMTNodeHandle();
00086
00087 _currentPose = result->description.initialPose;
00088
00089 _previousPose = _currentPose;
00090
00091 for ( unsigned int laserIter = 0;
00092 laserIter < result->description.laserSensors.size(); laserIter++ )
00093 {
00094 _sensors.push_back( SensorPtr(
00095 new Laser( _map,
00096 result->description.laserSensors[laserIter], getName(), n ) ) );
00097 }
00098 for ( unsigned int sonarIter = 0;
00099 sonarIter < result->description.sonarSensors.size(); sonarIter++ )
00100 {
00101 _sensors.push_back( SensorPtr(
00102 new Sonar( _map,
00103 result->description.sonarSensors[sonarIter], getName(), n ) ) );
00104 }
00105 for ( unsigned int rfidReaderIter = 0;
00106 rfidReaderIter < result->description.rfidSensors.size();
00107 rfidReaderIter++ )
00108 {
00109 _sensors.push_back( SensorPtr(
00110 new RfidReader( _map,
00111 result->description.rfidSensors[rfidReaderIter], getName(), n ) ) );
00112 }
00113 for ( unsigned int co2SensorIter = 0;
00114 co2SensorIter < result->description.co2Sensors.size();
00115 co2SensorIter++ )
00116 {
00117 _sensors.push_back( SensorPtr(
00118 new CO2Sensor( _map,
00119 result->description.co2Sensors[co2SensorIter], getName(), n ) ) );
00120 }
00121 for ( unsigned int thermalSensorIter = 0;
00122 thermalSensorIter < result->description.thermalSensors.size();
00123 thermalSensorIter++ )
00124 {
00125 _sensors.push_back( SensorPtr(
00126 new ThermalSensor( _map,
00127 result->description.thermalSensors[thermalSensorIter], getName(), n ) ) );
00128 }
00129 for ( unsigned int soundSensorIter = 0;
00130 soundSensorIter < result->description.soundSensors.size();
00131 soundSensorIter++ )
00132 {
00133 _sensors.push_back( SensorPtr(
00134 new SoundSensor( _map,
00135 result->description.soundSensors[soundSensorIter], getName(), n ) ) );
00136 }
00137
00138 if( result->description.footprint.points.size() == 0 ) {
00139 float radius = result->description.footprint.radius;
00140 for(unsigned int i = 0 ; i < 360 ; i++)
00141 {
00142 float x = cos(i * 3.14159265359 / 180.0) * radius;
00143 float y = sin(i * 3.14159265359 / 180.0) * radius;
00144 _footprint.push_back( std::pair<float,float>(x,y));
00145 }
00146 } else {
00147 for( unsigned int i = 0 ;
00148 i < result->description.footprint.points.size() ;
00149 i++ ) {
00150 geometry_msgs::Point p = result->description.footprint.points[i];
00151 _footprint.push_back( std::pair<float,float>(p.x, p.y));
00152 }
00153 }
00154
00155 std::string motion_model = result->description.kinematicModel.type;
00156 stdr_msgs::KinematicMsg p = result->description.kinematicModel;
00157
00158 if(motion_model == "ideal")
00159 {
00160 _motionControllerPtr.reset(
00161 new IdealMotionController(_currentPose, _tfBroadcaster, n, getName(), p));
00162 }
00163 else if(motion_model == "omni")
00164 {
00165 _motionControllerPtr.reset(
00166 new OmniMotionController(_currentPose, _tfBroadcaster, n, getName(), p));
00167 }
00168 else
00169 {
00170
00171 _motionControllerPtr.reset(
00172 new IdealMotionController(_currentPose, _tfBroadcaster, n, getName(), p));
00173 }
00174
00175 _tfTimer.start();
00176 }
00177
00183 void Robot::mapCallback(const nav_msgs::OccupancyGridConstPtr& msg)
00184 {
00185 _map = *msg;
00186 }
00187
00194 bool Robot::moveRobotCallback(stdr_msgs::MoveRobot::Request& req,
00195 stdr_msgs::MoveRobot::Response& res)
00196 {
00197 if( collisionExistsNoPath(req.newPose) ||
00198 checkUnknownOccupancy(req.newPose) )
00199 {
00200 return false;
00201 }
00202
00203 _currentPose = req.newPose;
00204
00205 _previousPose = _currentPose;
00206
00207 _motionControllerPtr->setPose(_previousPose);
00208 return true;
00209 }
00210
00215 bool Robot::collisionExistsNoPath(
00216 const geometry_msgs::Pose2D& newPose)
00217 {
00218 if(_map.info.width == 0 || _map.info.height == 0)
00219 {
00220 return false;
00221 }
00222
00223 int xMap = newPose.x / _map.info.resolution;
00224 int yMap = newPose.y / _map.info.resolution;
00225
00226 for(unsigned int i = 0 ; i < _footprint.size() ; i++)
00227 {
00228 double x = _footprint[i].first * cos(newPose.theta) -
00229 _footprint[i].second * sin(newPose.theta);
00230 double y = _footprint[i].first * sin(newPose.theta) +
00231 _footprint[i].second * cos(newPose.theta);
00232
00233 int xx = xMap + (int)(x / _map.info.resolution);
00234 int yy = yMap + (int)(y / _map.info.resolution);
00235
00236 if(_map.data[ yy * _map.info.width + xx ] > 70)
00237 {
00238 return true;
00239 }
00240 }
00241 return false;
00242 }
00243
00249 bool Robot::checkUnknownOccupancy(
00250 const geometry_msgs::Pose2D& newPose)
00251 {
00252 if(_map.info.width == 0 || _map.info.height == 0)
00253 {
00254 return false;
00255 }
00256
00257 int xMap = newPose.x / _map.info.resolution;
00258 int yMap = newPose.y / _map.info.resolution;
00259
00260 if( _map.data[ yMap * _map.info.width + xMap ] == -1 )
00261 {
00262 return true;
00263 }
00264
00265 return false;
00266 }
00267
00276 std::vector<std::pair<int,int> > Robot::getPointsBetween(
00277 int x1, int y1, int x2, int y2)
00278 {
00279 std::vector<std::pair<int,int> > points;
00280
00281 float angle = atan2(y2 - y1, x2 - x1);
00282 float dist = sqrt( pow(x2 - x1, 2) + pow(y2 - y1, 2));
00283
00284 int d = 0;
00285
00286 while(d < dist)
00287 {
00288 int x = x1 + d * cos(angle);
00289 int y = y1 + d * sin(angle);
00290 points.push_back(std::pair<int,int>(x,y));
00291 d++;
00292 }
00293
00294 return points;
00295 }
00296
00301 bool Robot::collisionExists(
00302 const geometry_msgs::Pose2D& newPose,
00303 const geometry_msgs::Pose2D& previousPose)
00304 {
00305 if(_map.info.width == 0 || _map.info.height == 0)
00306 return false;
00307
00308 int xMapPrev, xMap, yMapPrev, yMap;
00309 bool movingForward, movingUpward;
00310
00311
00312 movingForward = _previousMovementXAxis? false: true;
00313 if ( fabs(previousPose.x - newPose.x) > 0.001)
00314 {
00315 movingForward = (previousPose.x > newPose.x)? false: true;
00316 _previousMovementXAxis = movingForward;
00317 }
00318 movingUpward = _previousMovementYAxis? false: true;
00319 if ( fabs(previousPose.y - newPose.y) > 0.001)
00320 {
00321 movingUpward = (previousPose.y > newPose.y)? false: true;
00322 _previousMovementYAxis = movingUpward;
00323 }
00324
00325 xMapPrev = movingForward? (int)( previousPose.x / _map.info.resolution ):
00326 ceil( previousPose.x / _map.info.resolution );
00327 xMap = movingForward? ceil( newPose.x / _map.info.resolution ):
00328 (int)( newPose.x / _map.info.resolution );
00329
00330 yMapPrev = movingUpward? (int)( previousPose.y / _map.info.resolution ):
00331 ceil( previousPose.y / _map.info.resolution );
00332 yMap = movingUpward? ceil( newPose.y / _map.info.resolution ):
00333 (int)( newPose.y / _map.info.resolution );
00334
00335 float angle = atan2(yMap - yMapPrev, xMap - xMapPrev);
00336 int x = xMapPrev;
00337 int y = yMapPrev;
00338 int d = 2;
00339
00340 while(pow(xMap - x,2) + pow(yMap - y,2) > 1)
00341 {
00342 x = xMapPrev +
00343 ( movingForward? ceil( cos(angle) * d ): (int)( cos(angle) * d ) );
00344 y = yMapPrev +
00345 ( movingUpward? ceil( sin(angle) * d ): (int)( sin(angle) * d ) );
00346
00347 for(unsigned int i = 0 ; i < _footprint.size() ; i++)
00348 {
00349 int index_1 = i;
00350 int index_2 = (i + 1) % _footprint.size();
00351
00352
00353 double footprint_x_1 = _footprint[index_1].first * cos(newPose.theta) -
00354 _footprint[index_1].second * sin(newPose.theta);
00355 double footprint_y_1 = _footprint[index_1].first * sin(newPose.theta) +
00356 _footprint[index_1].second * cos(newPose.theta);
00357
00358 int xx1 = x + footprint_x_1 / _map.info.resolution;
00359 int yy1 = y + footprint_y_1 / _map.info.resolution;
00360
00361 double footprint_x_2 = _footprint[index_2].first * cos(newPose.theta) -
00362 _footprint[index_2].second * sin(newPose.theta);
00363 double footprint_y_2 = _footprint[index_2].first * sin(newPose.theta) +
00364 _footprint[index_2].second * cos(newPose.theta);
00365
00366 int xx2 = x + footprint_x_2 / _map.info.resolution;
00367 int yy2 = y + footprint_y_2 / _map.info.resolution;
00368
00369
00370 std::vector<std::pair<int,int> > pts =
00371 getPointsBetween(xx1,yy1,xx2,yy2);
00372
00373 for(unsigned int j = 0 ; j < pts.size() ; j++)
00374 {
00375 static int OF = 1;
00376 if(
00377 _map.data[ (pts[j].second - OF) *
00378 _map.info.width + pts[j].first - OF ] > 70 ||
00379 _map.data[ (pts[j].second - OF) *
00380 _map.info.width + pts[j].first ] > 70 ||
00381 _map.data[ (pts[j].second - OF) *
00382 _map.info.width + pts[j].first + OF ] > 70 ||
00383 _map.data[ (pts[j].second) *
00384 _map.info.width + pts[j].first - OF ] > 70 ||
00385 _map.data[ (pts[j].second) *
00386 _map.info.width + pts[j].first + OF ] > 70 ||
00387 _map.data[ (pts[j].second + OF) *
00388 _map.info.width + pts[j].first - OF ] > 70 ||
00389 _map.data[ (pts[j].second + OF) *
00390 _map.info.width + pts[j].first ] > 70 ||
00391 _map.data[ (pts[j].second + OF) *
00392 _map.info.width + pts[j].first + OF ] > 70
00393 )
00394 {
00395 return true;
00396 }
00397 }
00398 }
00399 if ( (movingForward && xMap < x) || (movingUpward && yMap < y) ||
00400 (!movingForward && xMap > x) || (!movingUpward && yMap > y) )
00401 {
00402 break;
00403 }
00404 d++;
00405 }
00406 return false;
00407 }
00408
00413 void Robot::publishTransforms(const ros::TimerEvent&)
00414 {
00415 geometry_msgs::Pose2D pose = _motionControllerPtr->getPose();
00416 if( ! collisionExists(pose, _previousPose) )
00417 {
00418 _previousPose = pose;
00419 }
00420 else
00421 {
00422 _motionControllerPtr->setPose(_previousPose);
00423 }
00425 tf::Vector3 translation(_previousPose.x, _previousPose.y, 0);
00426 tf::Quaternion rotation;
00427 rotation.setRPY(0, 0, _previousPose.theta);
00428
00429 tf::Transform mapToRobot(rotation, translation);
00430
00431 _tfBroadcaster.sendTransform(tf::StampedTransform(
00432 mapToRobot, ros::Time::now(), "map_static", getName()));
00433
00435 nav_msgs::Odometry odom;
00436 odom.header.stamp = ros::Time::now();
00437 odom.header.frame_id = "map_static";
00438 odom.child_frame_id = getName();
00439 odom.pose.pose.position.x = _previousPose.x;
00440 odom.pose.pose.position.y = _previousPose.y;
00441 odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(
00442 _previousPose.theta);
00443 odom.twist.twist = _motionControllerPtr->getVelocity();
00444
00445 _odomPublisher.publish(odom);
00446
00448 for (int i = 0; i < _sensors.size(); i++) {
00449 geometry_msgs::Pose2D sensorPose = _sensors[i]->getSensorPose();
00450
00451 tf::Vector3 trans(sensorPose.x, sensorPose.y, 0);
00452 tf::Quaternion rot;
00453 rot.setRPY(0, 0, sensorPose.theta);
00454
00455 tf::Transform robotToSensor(rot, trans);
00456
00457 _tfBroadcaster.sendTransform(
00458 tf::StampedTransform(
00459 robotToSensor,
00460 ros::Time::now(),
00461 getName(),
00462 _sensors[i]->getFrameId()));
00463 }
00464 }
00465
00470 Robot::~Robot()
00471 {
00473 }
00474
00475 }