23 #include <nodelet/NodeletUnload.h> 49 _registerClientPtr.reset(
52 _registerClientPtr->waitForServer();
54 stdr_msgs::RegisterRobotGoal goal;
56 _registerClientPtr->sendGoal(goal,
57 boost::bind(&Robot::initializeRobot,
this, _1, _2));
59 _mapSubscriber = n.
subscribe(
"map", 1, &Robot::mapCallback,
this);
61 getName() +
"/replace", &Robot::moveRobotCallback,
this);
65 ros::Duration(0.1), &Robot::publishTransforms,
this,
false,
false);
74 void Robot::initializeRobot(
76 const stdr_msgs::RegisterRobotResultConstPtr result)
87 _currentPose = result->description.initialPose;
89 _previousPose = _currentPose;
91 for (
unsigned int laserIter = 0;
92 laserIter < result->description.laserSensors.size(); laserIter++ )
96 result->description.laserSensors[laserIter],
getName(), n ) ) );
98 for (
unsigned int sonarIter = 0;
99 sonarIter < result->description.sonarSensors.size(); sonarIter++ )
103 result->description.sonarSensors[sonarIter],
getName(), n ) ) );
105 for (
unsigned int rfidReaderIter = 0;
106 rfidReaderIter < result->description.rfidSensors.size();
111 result->description.rfidSensors[rfidReaderIter],
getName(), n ) ) );
113 for (
unsigned int co2SensorIter = 0;
114 co2SensorIter < result->description.co2Sensors.size();
119 result->description.co2Sensors[co2SensorIter],
getName(), n ) ) );
121 for (
unsigned int thermalSensorIter = 0;
122 thermalSensorIter < result->description.thermalSensors.size();
123 thermalSensorIter++ )
127 result->description.thermalSensors[thermalSensorIter],
getName(), n ) ) );
129 for (
unsigned int soundSensorIter = 0;
130 soundSensorIter < result->description.soundSensors.size();
135 result->description.soundSensors[soundSensorIter],
getName(), n ) ) );
138 if( result->description.footprint.points.size() == 0 ) {
139 float radius = result->description.footprint.radius;
140 for(
unsigned int i = 0 ; i < 360 ; i++)
142 float x = cos(i * 3.14159265359 / 180.0) * radius;
143 float y = sin(i * 3.14159265359 / 180.0) * radius;
144 _footprint.push_back( std::pair<float,float>(x,y));
147 for(
unsigned int i = 0 ;
148 i < result->description.footprint.points.size() ;
150 geometry_msgs::Point p = result->description.footprint.points[i];
151 _footprint.push_back( std::pair<float,float>(p.x, p.y));
155 std::string motion_model = result->description.kinematicModel.type;
156 stdr_msgs::KinematicMsg p = result->description.kinematicModel;
158 if(motion_model ==
"ideal")
160 _motionControllerPtr.reset(
163 else if(motion_model ==
"omni")
165 _motionControllerPtr.reset(
171 _motionControllerPtr.reset(
183 void Robot::mapCallback(
const nav_msgs::OccupancyGridConstPtr& msg)
194 bool Robot::moveRobotCallback(stdr_msgs::MoveRobot::Request& req,
195 stdr_msgs::MoveRobot::Response& res)
197 if( collisionExistsNoPath(req.newPose) ||
198 checkUnknownOccupancy(req.newPose) )
203 _currentPose = req.newPose;
205 _previousPose = _currentPose;
207 _motionControllerPtr->setPose(_previousPose);
215 bool Robot::collisionExistsNoPath(
216 const geometry_msgs::Pose2D& newPose)
218 if(_map.info.width == 0 || _map.info.height == 0)
223 int xMap = newPose.x / _map.info.resolution;
224 int yMap = newPose.y / _map.info.resolution;
226 for(
unsigned int i = 0 ; i < _footprint.size() ; i++)
228 double x = _footprint[i].first * cos(newPose.theta) -
229 _footprint[i].second * sin(newPose.theta);
230 double y = _footprint[i].first * sin(newPose.theta) +
231 _footprint[i].second * cos(newPose.theta);
233 int xx = xMap + (int)(x / _map.info.resolution);
234 int yy = yMap + (int)(y / _map.info.resolution);
236 if(_map.data[ yy * _map.info.width + xx ] > 70)
249 bool Robot::checkUnknownOccupancy(
250 const geometry_msgs::Pose2D& newPose)
252 if(_map.info.width == 0 || _map.info.height == 0)
257 int xMap = newPose.x / _map.info.resolution;
258 int yMap = newPose.y / _map.info.resolution;
260 if( _map.data[ yMap * _map.info.width + xMap ] == -1 )
276 std::vector<std::pair<int,int> > Robot::getPointsBetween(
277 int x1,
int y1,
int x2,
int y2)
279 std::vector<std::pair<int,int> > points;
281 float angle = atan2(y2 - y1, x2 - x1);
282 float dist = sqrt( pow(x2 - x1, 2) + pow(y2 - y1, 2));
288 int x = x1 + d * cos(angle);
289 int y = y1 + d * sin(angle);
290 points.push_back(std::pair<int,int>(x,y));
301 bool Robot::collisionExists(
302 const geometry_msgs::Pose2D& newPose,
303 const geometry_msgs::Pose2D& previousPose)
305 if(_map.info.width == 0 || _map.info.height == 0)
308 int xMapPrev, xMap, yMapPrev, yMap;
309 bool movingForward, movingUpward;
312 movingForward = _previousMovementXAxis?
false:
true;
313 if ( fabs(previousPose.x - newPose.x) > 0.001)
315 movingForward = (previousPose.x > newPose.x)?
false:
true;
316 _previousMovementXAxis = movingForward;
318 movingUpward = _previousMovementYAxis?
false:
true;
319 if ( fabs(previousPose.y - newPose.y) > 0.001)
321 movingUpward = (previousPose.y > newPose.y)?
false:
true;
322 _previousMovementYAxis = movingUpward;
325 xMapPrev = movingForward? (int)( previousPose.x / _map.info.resolution ):
326 ceil( previousPose.x / _map.info.resolution );
327 xMap = movingForward? ceil( newPose.x / _map.info.resolution ):
328 (int)( newPose.x / _map.info.resolution );
330 yMapPrev = movingUpward? (int)( previousPose.y / _map.info.resolution ):
331 ceil( previousPose.y / _map.info.resolution );
332 yMap = movingUpward? ceil( newPose.y / _map.info.resolution ):
333 (int)( newPose.y / _map.info.resolution );
335 float angle = atan2(yMap - yMapPrev, xMap - xMapPrev);
340 while(pow(xMap - x,2) + pow(yMap - y,2) > 1)
343 ( movingForward? ceil( cos(angle) * d ): (int)( cos(angle) * d ) );
345 ( movingUpward? ceil( sin(angle) * d ): (int)( sin(angle) * d ) );
347 for(
unsigned int i = 0 ; i < _footprint.size() ; i++)
350 int index_2 = (i + 1) % _footprint.size();
353 double footprint_x_1 = _footprint[index_1].first * cos(newPose.theta) -
354 _footprint[index_1].second * sin(newPose.theta);
355 double footprint_y_1 = _footprint[index_1].first * sin(newPose.theta) +
356 _footprint[index_1].second * cos(newPose.theta);
358 int xx1 = x + footprint_x_1 / _map.info.resolution;
359 int yy1 = y + footprint_y_1 / _map.info.resolution;
361 double footprint_x_2 = _footprint[index_2].first * cos(newPose.theta) -
362 _footprint[index_2].second * sin(newPose.theta);
363 double footprint_y_2 = _footprint[index_2].first * sin(newPose.theta) +
364 _footprint[index_2].second * cos(newPose.theta);
366 int xx2 = x + footprint_x_2 / _map.info.resolution;
367 int yy2 = y + footprint_y_2 / _map.info.resolution;
370 std::vector<std::pair<int,int> > pts =
371 getPointsBetween(xx1,yy1,xx2,yy2);
373 for(
unsigned int j = 0 ; j < pts.size() ; j++)
377 _map.data[ (pts[j].second - OF) *
378 _map.info.width + pts[j].first - OF ] > 70 ||
379 _map.data[ (pts[j].second - OF) *
380 _map.info.width + pts[j].first ] > 70 ||
381 _map.data[ (pts[j].second - OF) *
382 _map.info.width + pts[j].first + OF ] > 70 ||
383 _map.data[ (pts[j].second) *
384 _map.info.width + pts[j].first - OF ] > 70 ||
385 _map.data[ (pts[j].second) *
386 _map.info.width + pts[j].first + OF ] > 70 ||
387 _map.data[ (pts[j].second + OF) *
388 _map.info.width + pts[j].first - OF ] > 70 ||
389 _map.data[ (pts[j].second + OF) *
390 _map.info.width + pts[j].first ] > 70 ||
391 _map.data[ (pts[j].second + OF) *
392 _map.info.width + pts[j].first + OF ] > 70
399 if ( (movingForward && xMap < x) || (movingUpward && yMap < y) ||
400 (!movingForward && xMap > x) || (!movingUpward && yMap > y) )
415 geometry_msgs::Pose2D pose = _motionControllerPtr->getPose();
416 if( ! collisionExists(pose, _previousPose) )
418 _previousPose = pose;
422 _motionControllerPtr->setPose(_previousPose);
425 tf::Vector3 translation(_previousPose.x, _previousPose.y, 0);
427 rotation.
setRPY(0, 0, _previousPose.theta);
435 nav_msgs::Odometry odom;
437 odom.header.frame_id =
"map_static";
438 odom.child_frame_id =
getName();
439 odom.pose.pose.position.x = _previousPose.x;
440 odom.pose.pose.position.y = _previousPose.y;
442 _previousPose.theta);
443 odom.twist.twist = _motionControllerPtr->getVelocity();
445 _odomPublisher.publish(odom);
448 for (
int i = 0; i < _sensors.size(); i++) {
449 geometry_msgs::Pose2D sensorPose = _sensors[i]->getSensorPose();
453 rot.
setRPY(0, 0, sensorPose.theta);
457 _tfBroadcaster.sendTransform(
const std::string & getFrameId(const T &t)
#define NODELET_ERROR(...)
Represents one robot in STDR. Inherts publicly from nodelet::Nodelet.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
The main namespace for STDR Robot.
std::string getName(void *handle)
boost::shared_ptr< Sensor > SensorPtr
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
A class that provides co2 sensor implementation. \ Inherits publicly Sensor.
A class that provides motion controller implementation. \ Inherits publicly MotionController.
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define NODELET_INFO(...)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
A class that provides motion controller implementation. Inherits publicly MotionController.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
actionlib::SimpleActionClient< stdr_msgs::RegisterRobotAction > RegisterRobotClient
A class that provides laser implementation. Inherits publicly Sensor.