stdr_robot.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
22 #include <stdr_robot/stdr_robot.h>
23 #include <nodelet/NodeletUnload.h>
25 
27 
28 namespace stdr_robot
29 {
34  Robot::Robot(void)
35  {
36 
37  }
38 
43  void Robot::onInit()
44  {
45  ros::NodeHandle n = getMTNodeHandle();
46 
47  _odomPublisher = n.advertise<nav_msgs::Odometry>(getName() + "/odom", 10);
48 
49  _registerClientPtr.reset(
50  new RegisterRobotClient(n, "stdr_server/register_robot", true) );
51 
52  _registerClientPtr->waitForServer();
53 
54  stdr_msgs::RegisterRobotGoal goal;
55  goal.name = getName();
56  _registerClientPtr->sendGoal(goal,
57  boost::bind(&Robot::initializeRobot, this, _1, _2));
58 
59  _mapSubscriber = n.subscribe("map", 1, &Robot::mapCallback, this);
60  _moveRobotService = n.advertiseService(
61  getName() + "/replace", &Robot::moveRobotCallback, this);
62 
63  //we should not start the timer, until we hame a motion controller
64  _tfTimer = n.createTimer(
65  ros::Duration(0.1), &Robot::publishTransforms, this, false, false);
66  }
67 
74  void Robot::initializeRobot(
76  const stdr_msgs::RegisterRobotResultConstPtr result)
77  {
78 
79  if (state == state.ABORTED) {
80  NODELET_ERROR("Something really bad happened...");
81  return;
82  }
83 
84  NODELET_INFO("Loaded new robot, %s", getName().c_str());
85  ros::NodeHandle n = getMTNodeHandle();
86 
87  _currentPose = result->description.initialPose;
88 
89  _previousPose = _currentPose;
90 
91  for ( unsigned int laserIter = 0;
92  laserIter < result->description.laserSensors.size(); laserIter++ )
93  {
94  _sensors.push_back( SensorPtr(
95  new Laser( _map,
96  result->description.laserSensors[laserIter], getName(), n ) ) );
97  }
98  for ( unsigned int sonarIter = 0;
99  sonarIter < result->description.sonarSensors.size(); sonarIter++ )
100  {
101  _sensors.push_back( SensorPtr(
102  new Sonar( _map,
103  result->description.sonarSensors[sonarIter], getName(), n ) ) );
104  }
105  for ( unsigned int rfidReaderIter = 0;
106  rfidReaderIter < result->description.rfidSensors.size();
107  rfidReaderIter++ )
108  {
109  _sensors.push_back( SensorPtr(
110  new RfidReader( _map,
111  result->description.rfidSensors[rfidReaderIter], getName(), n ) ) );
112  }
113  for ( unsigned int co2SensorIter = 0;
114  co2SensorIter < result->description.co2Sensors.size();
115  co2SensorIter++ )
116  {
117  _sensors.push_back( SensorPtr(
118  new CO2Sensor( _map,
119  result->description.co2Sensors[co2SensorIter], getName(), n ) ) );
120  }
121  for ( unsigned int thermalSensorIter = 0;
122  thermalSensorIter < result->description.thermalSensors.size();
123  thermalSensorIter++ )
124  {
125  _sensors.push_back( SensorPtr(
126  new ThermalSensor( _map,
127  result->description.thermalSensors[thermalSensorIter], getName(), n ) ) );
128  }
129  for ( unsigned int soundSensorIter = 0;
130  soundSensorIter < result->description.soundSensors.size();
131  soundSensorIter++ )
132  {
133  _sensors.push_back( SensorPtr(
134  new SoundSensor( _map,
135  result->description.soundSensors[soundSensorIter], getName(), n ) ) );
136  }
137 
138  if( result->description.footprint.points.size() == 0 ) {
139  float radius = result->description.footprint.radius;
140  for(unsigned int i = 0 ; i < 360 ; i++)
141  {
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));
145  }
146  } else {
147  for( unsigned int i = 0 ;
148  i < result->description.footprint.points.size() ;
149  i++ ) {
150  geometry_msgs::Point p = result->description.footprint.points[i];
151  _footprint.push_back( std::pair<float,float>(p.x, p.y));
152  }
153  }
154 
155  std::string motion_model = result->description.kinematicModel.type;
156  stdr_msgs::KinematicMsg p = result->description.kinematicModel;
157 
158  if(motion_model == "ideal")
159  {
160  _motionControllerPtr.reset(
161  new IdealMotionController(_currentPose, _tfBroadcaster, n, getName(), p));
162  }
163  else if(motion_model == "omni")
164  {
165  _motionControllerPtr.reset(
166  new OmniMotionController(_currentPose, _tfBroadcaster, n, getName(), p));
167  }
168  else
169  {
170  // If no motion model is specified or an invalid type declared use ideal
171  _motionControllerPtr.reset(
172  new IdealMotionController(_currentPose, _tfBroadcaster, n, getName(), p));
173  }
174 
175  _tfTimer.start();
176  }
177 
183  void Robot::mapCallback(const nav_msgs::OccupancyGridConstPtr& msg)
184  {
185  _map = *msg;
186  }
187 
194  bool Robot::moveRobotCallback(stdr_msgs::MoveRobot::Request& req,
195  stdr_msgs::MoveRobot::Response& res)
196  {
197  if( collisionExistsNoPath(req.newPose) ||
198  checkUnknownOccupancy(req.newPose) )
199  {
200  return false;
201  }
202 
203  _currentPose = req.newPose;
204 
205  _previousPose = _currentPose;
206 
207  _motionControllerPtr->setPose(_previousPose);
208  return true;
209  }
210 
215  bool Robot::collisionExistsNoPath(
216  const geometry_msgs::Pose2D& newPose)
217  {
218  if(_map.info.width == 0 || _map.info.height == 0)
219  {
220  return false;
221  }
222 
223  int xMap = newPose.x / _map.info.resolution;
224  int yMap = newPose.y / _map.info.resolution;
225 
226  for(unsigned int i = 0 ; i < _footprint.size() ; i++)
227  {
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);
232 
233  int xx = xMap + (int)(x / _map.info.resolution);
234  int yy = yMap + (int)(y / _map.info.resolution);
235 
236  if(_map.data[ yy * _map.info.width + xx ] > 70)
237  {
238  return true;
239  }
240  }
241  return false;
242  }
243 
249  bool Robot::checkUnknownOccupancy(
250  const geometry_msgs::Pose2D& newPose)
251  {
252  if(_map.info.width == 0 || _map.info.height == 0)
253  {
254  return false;
255  }
256 
257  int xMap = newPose.x / _map.info.resolution;
258  int yMap = newPose.y / _map.info.resolution;
259 
260  if( _map.data[ yMap * _map.info.width + xMap ] == -1 )
261  {
262  return true;
263  }
264 
265  return false;
266  }
267 
276  std::vector<std::pair<int,int> > Robot::getPointsBetween(
277  int x1, int y1, int x2, int y2)
278  {
279  std::vector<std::pair<int,int> > points;
280 
281  float angle = atan2(y2 - y1, x2 - x1);
282  float dist = sqrt( pow(x2 - x1, 2) + pow(y2 - y1, 2));
283 
284  int d = 0;
285 
286  while(d < dist)
287  {
288  int x = x1 + d * cos(angle);
289  int y = y1 + d * sin(angle);
290  points.push_back(std::pair<int,int>(x,y));
291  d++;
292  }
293 
294  return points;
295  }
296 
301  bool Robot::collisionExists(
302  const geometry_msgs::Pose2D& newPose,
303  const geometry_msgs::Pose2D& previousPose)
304  {
305  if(_map.info.width == 0 || _map.info.height == 0)
306  return false;
307 
308  int xMapPrev, xMap, yMapPrev, yMap;
309  bool movingForward, movingUpward;
310 
311  //Check robot's previous direction to prevent getting stuck when colliding
312  movingForward = _previousMovementXAxis? false: true;
313  if ( fabs(previousPose.x - newPose.x) > 0.001)
314  {
315  movingForward = (previousPose.x > newPose.x)? false: true;
316  _previousMovementXAxis = movingForward;
317  }
318  movingUpward = _previousMovementYAxis? false: true;
319  if ( fabs(previousPose.y - newPose.y) > 0.001)
320  {
321  movingUpward = (previousPose.y > newPose.y)? false: true;
322  _previousMovementYAxis = movingUpward;
323  }
324 
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 );
329 
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 );
334 
335  float angle = atan2(yMap - yMapPrev, xMap - xMapPrev);
336  int x = xMapPrev;
337  int y = yMapPrev;
338  int d = 2;
339 
340  while(pow(xMap - x,2) + pow(yMap - y,2) > 1)
341  {
342  x = xMapPrev +
343  ( movingForward? ceil( cos(angle) * d ): (int)( cos(angle) * d ) );
344  y = yMapPrev +
345  ( movingUpward? ceil( sin(angle) * d ): (int)( sin(angle) * d ) );
346  //Check all footprint points
347  for(unsigned int i = 0 ; i < _footprint.size() ; i++)
348  {
349  int index_1 = i;
350  int index_2 = (i + 1) % _footprint.size();
351 
352  // Get two consecutive footprint points
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);
357 
358  int xx1 = x + footprint_x_1 / _map.info.resolution;
359  int yy1 = y + footprint_y_1 / _map.info.resolution;
360 
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);
365 
366  int xx2 = x + footprint_x_2 / _map.info.resolution;
367  int yy2 = y + footprint_y_2 / _map.info.resolution;
368 
369  //Here check all the points between the vertexes
370  std::vector<std::pair<int,int> > pts =
371  getPointsBetween(xx1,yy1,xx2,yy2);
372 
373  for(unsigned int j = 0 ; j < pts.size() ; j++)
374  {
375  static int OF = 1;
376  if(
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
393  )
394  {
395  return true;
396  }
397  }
398  }
399  if ( (movingForward && xMap < x) || (movingUpward && yMap < y) ||
400  (!movingForward && xMap > x) || (!movingUpward && yMap > y) )
401  {
402  break;
403  }
404  d++;
405  }
406  return false;
407  }
408 
413  void Robot::publishTransforms(const ros::TimerEvent&)
414  {
415  geometry_msgs::Pose2D pose = _motionControllerPtr->getPose();
416  if( ! collisionExists(pose, _previousPose) )
417  {
418  _previousPose = pose;
419  }
420  else
421  {
422  _motionControllerPtr->setPose(_previousPose);
423  }
425  tf::Vector3 translation(_previousPose.x, _previousPose.y, 0);
426  tf::Quaternion rotation;
427  rotation.setRPY(0, 0, _previousPose.theta);
428 
429  tf::Transform mapToRobot(rotation, translation);
430 
431  _tfBroadcaster.sendTransform(tf::StampedTransform(
432  mapToRobot, ros::Time::now(), "map_static", getName()));
433 
435  nav_msgs::Odometry odom;
436  odom.header.stamp = ros::Time::now();
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;
441  odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(
442  _previousPose.theta);
443  odom.twist.twist = _motionControllerPtr->getVelocity();
444 
445  _odomPublisher.publish(odom);
446 
448  for (int i = 0; i < _sensors.size(); i++) {
449  geometry_msgs::Pose2D sensorPose = _sensors[i]->getSensorPose();
450 
451  tf::Vector3 trans(sensorPose.x, sensorPose.y, 0);
452  tf::Quaternion rot;
453  rot.setRPY(0, 0, sensorPose.theta);
454 
455  tf::Transform robotToSensor(rot, trans);
456 
457  _tfBroadcaster.sendTransform(
459  robotToSensor,
460  ros::Time::now(),
461  getName(),
462  _sensors[i]->getFrameId()));
463  }
464  }
465 
470  Robot::~Robot()
471  {
473  }
474 
475 } // namespace stdr_robot
d
const std::string & getFrameId(const T &t)
#define NODELET_ERROR(...)
Represents one robot in STDR. Inherts publicly from nodelet::Nodelet.
Definition: stdr_robot.h:59
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.
Definition: exceptions.h:27
std::string getName(void *handle)
boost::shared_ptr< Sensor > SensorPtr
Definition: sensor_base.h:141
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.
Definition: sonar.h:39
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)
static Time now()
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
Definition: stdr_robot.h:52
A class that provides laser implementation. Inherits publicly Sensor.
Definition: laser.h:39


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Mon Jun 10 2019 15:15:10