RosAria.cpp
Go to the documentation of this file.
1 #include <stdio.h>
2 #include <math.h>
3 #ifdef ADEPT_PKG
4  #include <Aria.h>
5 #else
6  #include <Aria/Aria.h>
7 #endif
8 #include "ros/ros.h"
9 #include "geometry_msgs/Twist.h"
10 #include "geometry_msgs/Pose.h"
11 #include "geometry_msgs/PoseStamped.h"
12 #include <sensor_msgs/PointCloud.h> //for sonar data
13 #include <sensor_msgs/PointCloud2.h>
14 #include <sensor_msgs/point_cloud_conversion.h> // can optionally publish sonar as new type pointcloud2
15 #include "nav_msgs/Odometry.h"
16 #include "rosaria/BumperState.h"
17 #include "tf/tf.h"
18 #include "tf/transform_listener.h" //for tf::getPrefixParam
20 #include "tf/transform_datatypes.h"
21 #include <dynamic_reconfigure/server.h>
22 #include <rosaria/RosAriaConfig.h>
23 #include "std_msgs/Float64.h"
24 #include "std_msgs/Float32.h"
25 #include "std_msgs/Int8.h"
26 #include "std_msgs/Bool.h"
27 #include "std_srvs/Empty.h"
28 
29 #include "LaserPublisher.h"
30 
31 #include <sstream>
32 
33 
51 {
52  public:
54  virtual ~RosAriaNode();
55 
56  public:
57  int Setup();
58  void cmdvel_cb( const geometry_msgs::TwistConstPtr &);
59  void cmdvel_watchdog(const ros::TimerEvent& event);
60  //void cmd_enable_motors_cb();
61  //void cmd_disable_motors_cb();
62  void spin();
63  void publish();
64  void sonarConnectCb();
65  void dynamic_reconfigureCB(rosaria::RosAriaConfig &config, uint32_t level);
66  void readParameters();
67 
68  protected:
75 
77  std_msgs::Int8 recharge_state;
78 
80 
82  std_msgs::Bool motors_state;
84 
86 
89  bool enable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
90  bool disable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
91 
95 
96  std::string serial_port;
98 
99  ArRobotConnector *conn;
100  ArLaserConnector *laserConnector;
101  ArRobot *robot;
102  nav_msgs::Odometry position;
103  rosaria::BumperState bumpers;
104  ArPose pos;
105  ArFunctorC<RosAriaNode> myPublishCB;
106  //ArRobot::ChargeState batteryCharge;
107 
108  //for odom->base_link transform
110  geometry_msgs::TransformStamped odom_trans;
111 
112  std::string frame_id_odom;
113  std::string frame_id_base_link;
114  std::string frame_id_bumper;
115  std::string frame_id_sonar;
116 
117  // flag indicating whether sonar was enabled or disabled on the robot
119 
120  // enable and publish sonar topics. set to true when first subscriber connects, set to false when last subscriber disconnects.
123 
124  // Debug Aria
126  std::string aria_log_filename;
127 
128  // Robot Calibration Parameters (see readParameters() function)
129  int TicksMM, DriftFactor, RevCount; //If TicksMM or RevCount are <0, don't use. If DriftFactor is -99999, don't use (DriftFactor could be 0 or negative).
130 
131  // dynamic_reconfigure
132  dynamic_reconfigure::Server<rosaria::RosAriaConfig> *dynamic_reconfigure_server;
133 
134  // whether to publish aria lasers
136 };
137 
139 {
140  // Robot Parameters. If a parameter was given and is nonzero, set it now.
141  // Otherwise, get default value for this robot (from getOrigRobotConfig()).
142  // Parameter values are stored in member variables for possible later use by the user with dynamic reconfigure.
143  robot->lock();
144  ros::NodeHandle n_("~");
145  if (n_.getParam("TicksMM", TicksMM) && TicksMM > 0)
146  {
147  ROS_INFO("Setting robot TicksMM from ROS Parameter: %d", TicksMM);
148  robot->comInt(93, TicksMM);
149  }
150  else
151  {
152  TicksMM = robot->getOrigRobotConfig()->getTicksMM();
153  ROS_INFO("This robot's TicksMM parameter: %d", TicksMM);
154  //n_.setParam( "TicksMM", TicksMM);
155  }
156 
157  if (n_.getParam("DriftFactor", DriftFactor) && DriftFactor != -99999)
158  {
159  ROS_INFO("Setting robot DriftFactor from ROS Parameter: %d", DriftFactor);
160  robot->comInt(89, DriftFactor);
161  }
162  else
163  {
164  DriftFactor = robot->getOrigRobotConfig()->getDriftFactor();
165  ROS_INFO("This robot's DriftFactor parameter: %d", DriftFactor);
166  //n_.setParam( "DriftFactor", DriftFactor);
167  }
168 
169  if (n_.getParam("RevCount", RevCount) && RevCount > 0)
170  {
171  ROS_INFO("Setting robot RevCount from ROS Parameter: %d", RevCount);
172  robot->comInt(88, RevCount);
173  }
174  else
175  {
176  RevCount = robot->getOrigRobotConfig()->getRevCount();
177  ROS_INFO("This robot's RevCount parameter: %d", RevCount);
178  //n_.setParam( "RevCount", RevCount);
179  }
180  robot->unlock();
181 }
182 
183 void RosAriaNode::dynamic_reconfigureCB(rosaria::RosAriaConfig &config, uint32_t level)
184 {
185  //
186  // Odometry Settings
187  //
188  robot->lock();
189  if(TicksMM != config.TicksMM && config.TicksMM > 0)
190  {
191  ROS_INFO("Setting TicksMM from Dynamic Reconfigure: %d -> %d ", TicksMM, config.TicksMM);
192  TicksMM = config.TicksMM;
193  robot->comInt(93, TicksMM);
194  }
195 
196  if(DriftFactor != config.DriftFactor && config.DriftFactor != -99999)
197  {
198  ROS_INFO("Setting DriftFactor from Dynamic Reconfigure: %d -> %d ", DriftFactor, config.DriftFactor);
199  DriftFactor = config.DriftFactor;
200  robot->comInt(89, DriftFactor);
201  }
202 
203  if(RevCount != config.RevCount && config.RevCount > 0)
204  {
205  ROS_INFO("Setting RevCount from Dynamic Reconfigure: %d -> %d ", RevCount, config.RevCount);
206  RevCount = config.RevCount;
207  robot->comInt(88, RevCount);
208  }
209 
210  //
211  // Acceleration Parameters
212  //
213  int value;
214  value = config.trans_accel * 1000;
215  if(value != robot->getTransAccel() && value > 0)
216  {
217  ROS_INFO("Setting TransAccel from Dynamic Reconfigure: %d", value);
218  robot->setTransAccel(value);
219  }
220 
221  value = config.trans_decel * 1000;
222  if(value != robot->getTransDecel() && value > 0)
223  {
224  ROS_INFO("Setting TransDecel from Dynamic Reconfigure: %d", value);
225  robot->setTransDecel(value);
226  }
227 
228  value = config.lat_accel * 1000;
229  if(value != robot->getLatAccel() && value > 0)
230  {
231  ROS_INFO("Setting LatAccel from Dynamic Reconfigure: %d", value);
232  if (robot->getAbsoluteMaxLatAccel() > 0 )
233  robot->setLatAccel(value);
234  }
235 
236  value = config.lat_decel * 1000;
237  if(value != robot->getLatDecel() && value > 0)
238  {
239  ROS_INFO("Setting LatDecel from Dynamic Reconfigure: %d", value);
240  if (robot->getAbsoluteMaxLatDecel() > 0 )
241  robot->setLatDecel(value);
242  }
243 
244  value = config.rot_accel * 180/M_PI;
245  if(value != robot->getRotAccel() && value > 0)
246  {
247  ROS_INFO("Setting RotAccel from Dynamic Reconfigure: %d", value);
248  robot->setRotAccel(value);
249  }
250 
251  value = config.rot_decel * 180/M_PI;
252  if(value != robot->getRotDecel() && value > 0)
253  {
254  ROS_INFO("Setting RotDecel from Dynamic Reconfigure: %d", value);
255  robot->setRotDecel(value);
256  }
257  robot->unlock();
258 }
259 
262 {
265  robot->lock();
267  {
268  robot->enableSonar();
269  sonar_enabled = false;
270  }
272  {
273  robot->disableSonar();
274  sonar_enabled = true;
275  }
276  robot->unlock();
277 }
278 
280  n(nh),
281  serial_port(""), serial_baud(0),
282  conn(NULL), laserConnector(NULL), robot(NULL),
285  debug_aria(false),
286  TicksMM(-1), DriftFactor(-99999), RevCount(-1),
287  publish_aria_lasers(false)
288 {
289  // read in runtime parameters
290 
291  // port and baud
292  n.param( "port", serial_port, std::string("/dev/ttyUSB0") );
293  ROS_INFO( "RosAria: set port: [%s]", serial_port.c_str() );
294 
295  n.param("baud", serial_baud, 0);
296  if(serial_baud != 0)
297  ROS_INFO("RosAria: set serial port baud rate %d", serial_baud);
298 
299  // handle debugging more elegantly
300  n.param( "debug_aria", debug_aria, false ); // default not to debug
301  n.param( "aria_log_filename", aria_log_filename, std::string("Aria.log") );
302 
303  // whether to connect to lasers using aria
304  n.param("publish_aria_lasers", publish_aria_lasers, false);
305 
306  // Get frame_ids to use.
307  n.param("odom_frame", frame_id_odom, std::string("odom"));
308  n.param("base_link_frame", frame_id_base_link, std::string("base_link"));
309  n.param("bumpers_frame", frame_id_bumper, std::string("bumpers"));
310  n.param("sonar_frame", frame_id_sonar, std::string("sonar"));
311 
312  // advertise services for data topics
313  // second argument to advertise() is queue size.
314  // other argmuments (optional) are callbacks, or a boolean "latch" flag (whether to send current data to new
315  // subscribers when they subscribe).
316  // See ros::NodeHandle API docs.
317  pose_pub = n.advertise<nav_msgs::Odometry>("pose",1000);
318  bumpers_pub = n.advertise<rosaria::BumperState>("bumper_state",1000);
319  sonar_pub = n.advertise<sensor_msgs::PointCloud>("sonar", 50,
320  boost::bind(&RosAriaNode::sonarConnectCb, this),
321  boost::bind(&RosAriaNode::sonarConnectCb, this));
322  sonar_pointcloud2_pub = n.advertise<sensor_msgs::PointCloud2>("sonar_pointcloud2", 50,
323  boost::bind(&RosAriaNode::sonarConnectCb, this),
324  boost::bind(&RosAriaNode::sonarConnectCb, this));
325 
326  voltage_pub = n.advertise<std_msgs::Float64>("battery_voltage", 1000);
327  recharge_state_pub = n.advertise<std_msgs::Int8>("battery_recharge_state", 5, true /*latch*/ );
328  recharge_state.data = -2;
329  state_of_charge_pub = n.advertise<std_msgs::Float32>("battery_state_of_charge", 100);
330 
331  motors_state_pub = n.advertise<std_msgs::Bool>("motors_state", 5, true /*latch*/ );
332  motors_state.data = false;
333  published_motors_state = false;
334 
335  // advertise enable/disable services
336  enable_srv = n.advertiseService("enable_motors", &RosAriaNode::enable_motors_cb, this);
337  disable_srv = n.advertiseService("disable_motors", &RosAriaNode::disable_motors_cb, this);
338 
340 }
341 
343 {
344  // disable motors and sonar.
345  robot->disableMotors();
346  robot->disableSonar();
347 
348  robot->stopRunning();
349  robot->waitForRunExit();
350  Aria::shutdown();
351 }
352 
354 {
355  // Note, various objects are allocated here which are never deleted (freed), since Setup() is only supposed to be
356  // called once per instance, and these objects need to persist until the process terminates.
357 
358  robot = new ArRobot();
359  ArArgumentBuilder *args = new ArArgumentBuilder(); // never freed
360  ArArgumentParser *argparser = new ArArgumentParser(args); // Warning never freed
361  argparser->loadDefaultArguments(); // adds any arguments given in /etc/Aria.args. Useful on robots with unusual serial port or baud rate (e.g. pioneer lx)
362 
363  // Now add any parameters given via ros params (see RosAriaNode constructor):
364 
365  // if serial port parameter contains a ':' character, then interpret it as hostname:tcpport
366  // for wireless serial connection. Otherwise, interpret it as a serial port name.
367  size_t colon_pos = serial_port.find(":");
368  if (colon_pos != std::string::npos)
369  {
370  args->add("-remoteHost"); // pass robot's hostname/IP address to Aria
371  args->add(serial_port.substr(0, colon_pos).c_str());
372  args->add("-remoteRobotTcpPort"); // pass robot's TCP port to Aria
373  args->add(serial_port.substr(colon_pos+1).c_str());
374  }
375  else
376  {
377  args->add("-robotPort %s", serial_port.c_str()); // pass robot's serial port to Aria
378  }
379 
380  // if a baud rate was specified in baud parameter
381  if(serial_baud != 0)
382  {
383  args->add("-robotBaud %d", serial_baud);
384  }
385 
386  if( debug_aria )
387  {
388  // turn on all ARIA debugging
389  args->add("-robotLogPacketsReceived"); // log received packets
390  args->add("-robotLogPacketsSent"); // log sent packets
391  args->add("-robotLogVelocitiesReceived"); // log received velocities
392  args->add("-robotLogMovementSent");
393  args->add("-robotLogMovementReceived");
394  ArLog::init(ArLog::File, ArLog::Verbose, aria_log_filename.c_str(), true);
395  }
396 
397 
398  // Connect to the robot
399  conn = new ArRobotConnector(argparser, robot); // warning never freed
400  if (!conn->connectRobot()) {
401  ROS_ERROR("RosAria: ARIA could not connect to robot! (Check ~port parameter is correct, and permissions on port device, or any errors reported above)");
402  return 1;
403  }
404 
406  laserConnector = new ArLaserConnector(argparser, robot, conn);
407 
408  // causes ARIA to load various robot-specific hardware parameters from the robot parameter file in /usr/local/Aria/params
409  if(!Aria::parseArgs())
410  {
411  ROS_ERROR("RosAria: ARIA error parsing ARIA startup parameters!");
412  return 1;
413  }
414 
415  readParameters();
416 
417  // Start dynamic_reconfigure server
418  dynamic_reconfigure_server = new dynamic_reconfigure::Server<rosaria::RosAriaConfig>;
419 
420  // Setup Parameter Minimums and maximums
421  rosaria::RosAriaConfig dynConf_min;
422  rosaria::RosAriaConfig dynConf_max;
423 
424  dynConf_max.trans_accel = robot->getAbsoluteMaxTransAccel() / 1000;
425  dynConf_max.trans_decel = robot->getAbsoluteMaxTransDecel() / 1000;
426  // TODO: Fix rqt dynamic_reconfigure gui to handle empty intervals
427  // Until then, set unit length interval.
428  dynConf_max.lat_accel = ((robot->getAbsoluteMaxLatAccel() > 0.0) ? robot->getAbsoluteMaxLatAccel() : 0.1) / 1000;
429  dynConf_max.lat_decel = ((robot->getAbsoluteMaxLatDecel() > 0.0) ? robot->getAbsoluteMaxLatDecel() : 0.1) / 1000;
430  dynConf_max.rot_accel = robot->getAbsoluteMaxRotAccel() * M_PI/180;
431  dynConf_max.rot_decel = robot->getAbsoluteMaxRotDecel() * M_PI/180;
432 
433  dynConf_min.trans_accel = 0;
434  dynConf_min.trans_decel = 0;
435  dynConf_min.lat_accel = 0;
436  dynConf_min.lat_decel = 0;
437  dynConf_min.rot_accel = 0;
438  dynConf_min.rot_decel = 0;
439 
440  dynConf_min.TicksMM = 0;
441  dynConf_max.TicksMM = 200;
442  dynConf_min.DriftFactor = -99999;
443  dynConf_max.DriftFactor = 32767;
444  dynConf_min.RevCount = 0;
445  dynConf_max.RevCount = 65535;
446 
447  dynamic_reconfigure_server->setConfigMax(dynConf_max);
448  dynamic_reconfigure_server->setConfigMin(dynConf_min);
449 
450 
451  rosaria::RosAriaConfig dynConf_default;
452  dynConf_default.trans_accel = robot->getTransAccel() / 1000;
453  dynConf_default.trans_decel = robot->getTransDecel() / 1000;
454  dynConf_default.lat_accel = robot->getLatAccel() / 1000;
455  dynConf_default.lat_decel = robot->getLatDecel() / 1000;
456  dynConf_default.rot_accel = robot->getRotAccel() * M_PI/180;
457  dynConf_default.rot_decel = robot->getRotDecel() * M_PI/180;
458 
459  dynConf_default.TicksMM = 0;
460  dynConf_default.DriftFactor = -99999;
461  dynConf_default.RevCount = 0;
462 
463  dynamic_reconfigure_server->setConfigDefault(dynConf_default);
464 
465  dynamic_reconfigure_server->setCallback(boost::bind(&RosAriaNode::dynamic_reconfigureCB, this, _1, _2));
466 
467 
468  // Enable the motors
469  robot->enableMotors();
470 
471  // disable sonars on startup
472  robot->disableSonar();
473 
474  // callback will be called by ArRobot background processing thread for every SIP data packet received from robot
475  robot->addSensorInterpTask("ROSPublishingTask", 100, &myPublishCB);
476 
477  // Initialize bumpers with robot number of bumpers
478  bumpers.front_bumpers.resize(robot->getNumFrontBumpers());
479  bumpers.rear_bumpers.resize(robot->getNumRearBumpers());
480 
481  // Run ArRobot background processing thread
482  robot->runAsync(true);
483 
484  // connect to lasers and create publishers
486  {
487  ROS_INFO_NAMED("rosaria", "rosaria: Connecting to laser(s) configured in ARIA parameter file(s)...");
488  if (!laserConnector->connectLasers())
489  {
490  ROS_FATAL_NAMED("rosaria", "rosaria: Error connecting to laser(s)...");
491  return 1;
492  }
493 
494  robot->lock();
495  const std::map<int, ArLaser*> *lasers = robot->getLaserMap();
496  ROS_INFO_NAMED("rosaria", "rosaria: there are %lu connected lasers", lasers->size());
497  for(std::map<int, ArLaser*>::const_iterator i = lasers->begin(); i != lasers->end(); ++i)
498  {
499  ArLaser *l = i->second;
500  int ln = i->first;
501  std::string tfname("laser");
502  if(lasers->size() > 1 || ln > 1) // no number if only one laser which is also laser 1
503  tfname += ln;
504  tfname += "_frame";
505  ROS_INFO_NAMED("rosaria", "rosaria: Creating publisher for laser #%d named %s with tf frame name %s", ln, l->getName(), tfname.c_str());
506  new LaserPublisher(l, n, true, tfname);
507  }
508  robot->unlock();
509  ROS_INFO_NAMED("rosaria", "rosaria: Done creating laser publishers");
510  }
511 
512  // subscribe to command topics
513  cmdvel_sub = n.subscribe( "cmd_vel", 1, (boost::function <void(const geometry_msgs::TwistConstPtr&)>)
514  boost::bind(&RosAriaNode::cmdvel_cb, this, _1 ));
515 
516  // register a watchdog for cmd_vel timeout
517  double cmdvel_timeout_param = 0.6;
518  n.param("cmd_vel_timeout", cmdvel_timeout_param, 0.6);
519  cmdvel_timeout = ros::Duration(cmdvel_timeout_param);
520  if (cmdvel_timeout_param > 0.0)
522 
523  ROS_INFO_NAMED("rosaria", "rosaria: Setup complete");
524  return 0;
525 }
526 
528 {
529  ros::spin();
530 }
531 
533 {
534  // Note, this is called via SensorInterpTask callback (myPublishCB, named "ROSPublishingTask"). ArRobot object 'robot' sholud not be locked or unlocked.
535  pos = robot->getPose();
537  pos.getY()/1000, 0)), position.pose.pose); //Aria returns pose in mm.
538  position.twist.twist.linear.x = robot->getVel()/1000.0; //Aria returns velocity in mm/s.
539  position.twist.twist.linear.y = robot->getLatVel()/1000.0;
540  position.twist.twist.angular.z = robot->getRotVel()*M_PI/180;
541 
542  position.header.frame_id = frame_id_odom;
543  position.child_frame_id = frame_id_base_link;
544  position.header.stamp = ros::Time::now();
546 
547  ROS_DEBUG("RosAria: publish: (time %f) pose x: %f, pose y: %f, pose angle: %f; linear vel x: %f, vel y: %f; angular vel z: %f",
548  position.header.stamp.toSec(),
549  (double)position.pose.pose.position.x,
550  (double)position.pose.pose.position.y,
551  (double)position.pose.pose.orientation.w,
552  (double)position.twist.twist.linear.x,
553  (double)position.twist.twist.linear.y,
554  (double)position.twist.twist.angular.z
555  );
556 
557  // publishing transform odom->base_link
558  odom_trans.header.stamp = ros::Time::now();
559  odom_trans.header.frame_id = frame_id_odom;
560  odom_trans.child_frame_id = frame_id_base_link;
561 
562  odom_trans.transform.translation.x = pos.getX()/1000;
563  odom_trans.transform.translation.y = pos.getY()/1000;
564  odom_trans.transform.translation.z = 0.0;
565  odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(pos.getTh()*M_PI/180);
566 
568 
569  // getStallValue returns 2 bytes with stall bit and bumper bits, packed as (00 00 FrontBumpers RearBumpers)
570  int stall = robot->getStallValue();
571  unsigned char front_bumpers = (unsigned char)(stall >> 8);
572  unsigned char rear_bumpers = (unsigned char)(stall);
573 
574  bumpers.header.frame_id = frame_id_bumper;
575  bumpers.header.stamp = ros::Time::now();
576 
577  std::stringstream bumper_info(std::stringstream::out);
578  // Bit 0 is for stall, next bits are for bumpers (leftmost is LSB)
579  for (unsigned int i=0; i<robot->getNumFrontBumpers(); i++)
580  {
581  bumpers.front_bumpers[i] = (front_bumpers & (1 << (i+1))) == 0 ? 0 : 1;
582  bumper_info << " " << (front_bumpers & (1 << (i+1)));
583  }
584  ROS_DEBUG("RosAria: Front bumpers:%s", bumper_info.str().c_str());
585 
586  bumper_info.str("");
587  // Rear bumpers have reverse order (rightmost is LSB)
588  unsigned int numRearBumpers = robot->getNumRearBumpers();
589  for (unsigned int i=0; i<numRearBumpers; i++)
590  {
591  bumpers.rear_bumpers[i] = (rear_bumpers & (1 << (numRearBumpers-i))) == 0 ? 0 : 1;
592  bumper_info << " " << (rear_bumpers & (1 << (numRearBumpers-i)));
593  }
594  ROS_DEBUG("RosAria: Rear bumpers:%s", bumper_info.str().c_str());
595 
597 
598  //Publish battery information
599  // TODO: Decide if BatteryVoltageNow (normalized to (0,12)V) is a better option
600  std_msgs::Float64 batteryVoltage;
601  batteryVoltage.data = robot->getRealBatteryVoltageNow();
602  voltage_pub.publish(batteryVoltage);
603 
604  if(robot->haveStateOfCharge())
605  {
606  std_msgs::Float32 soc;
607  soc.data = robot->getStateOfCharge()/100.0;
609  }
610 
611  // publish recharge state if changed
612  char s = robot->getChargeState();
613  if(s != recharge_state.data)
614  {
615  ROS_INFO("RosAria: publishing new recharge state %d.", s);
616  recharge_state.data = s;
618  }
619 
620  // publish motors state if changed
621  bool e = robot->areMotorsEnabled();
622  if(e != motors_state.data || !published_motors_state)
623  {
624  ROS_INFO("RosAria: publishing new motors state %d.", e);
625  motors_state.data = e;
627  published_motors_state = true;
628  }
629 
630  // Publish sonar information, if enabled.
632  {
633  sensor_msgs::PointCloud cloud; //sonar readings.
634  cloud.header.stamp = position.header.stamp; //copy time.
635  // sonar sensors relative to base_link
636  cloud.header.frame_id = frame_id_sonar;
637 
638 
639  std::stringstream sonar_debug_info; // Log debugging info
640  sonar_debug_info << "Sonar readings: ";
641 
642  for (int i = 0; i < robot->getNumSonar(); i++) {
643  ArSensorReading* reading = NULL;
644  reading = robot->getSonarReading(i);
645  if(!reading) {
646  ROS_WARN("RosAria: Did not receive a sonar reading.");
647  continue;
648  }
649 
650  // getRange() will return an integer between 0 and 5000 (5m)
651  sonar_debug_info << reading->getRange() << " ";
652 
653  // local (x,y). Appears to be from the centre of the robot, since values may
654  // exceed 5000. This is good, since it means we only need 1 transform.
655  // x & y seem to be swapped though, i.e. if the robot is driving north
656  // x is north/south and y is east/west.
657  //
658  //ArPose sensor = reading->getSensorPosition(); //position of sensor.
659  // sonar_debug_info << "(" << reading->getLocalX()
660  // << ", " << reading->getLocalY()
661  // << ") from (" << sensor.getX() << ", "
662  // << sensor.getY() << ") ;; " ;
663 
664  //add sonar readings (robot-local coordinate frame) to cloud
665  geometry_msgs::Point32 p;
666  p.x = reading->getLocalX() / 1000.0;
667  p.y = reading->getLocalY() / 1000.0;
668  p.z = 0.0;
669  cloud.points.push_back(p);
670  }
671  ROS_DEBUG_STREAM(sonar_debug_info.str());
672 
673  // publish topic(s)
674 
676  {
677  sensor_msgs::PointCloud2 cloud2;
679  {
680  ROS_WARN("Error converting sonar point cloud message to point_cloud2 type before publishing! Not publishing this time.");
681  }
682  else
683  {
685  }
686  }
687 
688  if(publish_sonar)
689  {
690  sonar_pub.publish(cloud);
691  }
692  } // end if sonar_enabled
693 }
694 
695 bool RosAriaNode::enable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
696 {
697  ROS_INFO("RosAria: Enable motors request.");
698  robot->lock();
699  if(robot->isEStopPressed())
700  ROS_WARN("RosAria: Warning: Enable motors requested, but robot also has E-Stop button pressed. Motors will not enable.");
701  robot->enableMotors();
702  robot->unlock();
703  // todo could wait and see if motors do become enabled, and send a response with an error flag if not
704  return true;
705 }
706 
707 bool RosAriaNode::disable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
708 {
709  ROS_INFO("RosAria: Disable motors request.");
710  robot->lock();
711  robot->disableMotors();
712  robot->unlock();
713  // todo could wait and see if motors do become disabled, and send a response with an error flag if not
714  return true;
715 }
716 
717 void
718 RosAriaNode::cmdvel_cb( const geometry_msgs::TwistConstPtr &msg)
719 {
721  ROS_INFO( "new speed: [%0.2f,%0.2f](%0.3f)", msg->linear.x*1e3, msg->angular.z, veltime.toSec() );
722 
723  robot->lock();
724  robot->setVel(msg->linear.x*1e3);
725  if(robot->hasLatVel())
726  robot->setLatVel(msg->linear.y*1e3);
727  robot->setRotVel(msg->angular.z*180/M_PI);
728  robot->unlock();
729  ROS_DEBUG("RosAria: sent vels to to aria (time %f): x vel %f mm/s, y vel %f mm/s, ang vel %f deg/s", veltime.toSec(),
730  (double) msg->linear.x * 1e3, (double) msg->linear.y * 1.3, (double) msg->angular.z * 180/M_PI);
731 }
732 
734 {
735  // stop robot if no cmd_vel message was received for 0.6 seconds
736  if (ros::Time::now() - veltime > ros::Duration(0.6))
737  {
738  robot->lock();
739  robot->setVel(0.0);
740  if(robot->hasLatVel())
741  robot->setLatVel(0.0);
742  robot->setRotVel(0.0);
743  robot->unlock();
744  }
745 }
746 
747 
748 int main( int argc, char** argv )
749 {
750  ros::init(argc,argv, "RosAria");
751  ros::NodeHandle n(std::string("~"));
752  Aria::init();
753 
754  RosAriaNode *node = new RosAriaNode(n);
755 
756  if( node->Setup() != 0 )
757  {
758  ROS_FATAL( "RosAria: ROS node setup failed... \n" );
759  return -1;
760  }
761 
762  node->spin();
763 
764  delete node;
765 
766  ROS_INFO( "RosAria: Quitting... \n" );
767  return 0;
768 
769 }
bool publish_aria_lasers
Definition: RosAria.cpp:135
int serial_baud
Definition: RosAria.cpp:97
ros::Duration cmdvel_timeout
Definition: RosAria.cpp:94
bool enable_motors_cb(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Definition: RosAria.cpp:695
#define ROS_FATAL(...)
ArPose pos
Definition: RosAria.cpp:104
#define ROS_INFO_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
std::string frame_id_bumper
Definition: RosAria.cpp:114
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::ServiceServer enable_srv
Definition: RosAria.cpp:87
geometry_msgs::TransformStamped odom_trans
Definition: RosAria.cpp:110
XmlRpcServer s
ros::Subscriber cmdvel_sub
Definition: RosAria.cpp:85
ArRobot * robot
Definition: RosAria.cpp:101
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish()
Definition: RosAria.cpp:532
void cmdvel_cb(const geometry_msgs::TwistConstPtr &)
Definition: RosAria.cpp:718
std::string serial_port
Definition: RosAria.cpp:96
int Setup()
Definition: RosAria.cpp:353
int DriftFactor
Definition: RosAria.cpp:129
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std_msgs::Int8 recharge_state
Definition: RosAria.cpp:77
nav_msgs::Odometry position
Definition: RosAria.cpp:102
#define ROS_WARN(...)
ros::NodeHandle n
Definition: RosAria.cpp:69
std::string aria_log_filename
Definition: RosAria.cpp:126
ros::Time veltime
Definition: RosAria.cpp:92
std::string frame_id_base_link
Definition: RosAria.cpp:113
bool debug_aria
Definition: RosAria.cpp:125
ROSCPP_DECL void spin(Spinner &spinner)
void readParameters()
Definition: RosAria.cpp:138
Node that interfaces between ROS and mobile robot base features via ARIA library. ...
Definition: RosAria.cpp:50
std_msgs::Bool motors_state
Definition: RosAria.cpp:82
bool publish_sonar_pointcloud2
Definition: RosAria.cpp:122
ros::Publisher sonar_pub
Definition: RosAria.cpp:72
RosAriaNode(ros::NodeHandle n)
Definition: RosAria.cpp:279
void spin()
Definition: RosAria.cpp:527
static Quaternion createQuaternionFromYaw(double yaw)
void dynamic_reconfigureCB(rosaria::RosAriaConfig &config, uint32_t level)
Definition: RosAria.cpp:183
ros::Publisher voltage_pub
Definition: RosAria.cpp:74
bool published_motors_state
Definition: RosAria.cpp:83
std::string frame_id_odom
Definition: RosAria.cpp:112
ArLaserConnector * laserConnector
Definition: RosAria.cpp:100
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool sonar_enabled
Definition: RosAria.cpp:118
void sendTransform(const StampedTransform &transform)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
rosaria::BumperState bumpers
Definition: RosAria.cpp:103
ros::Publisher sonar_pointcloud2_pub
Definition: RosAria.cpp:73
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pose_pub
Definition: RosAria.cpp:70
#define ROS_DEBUG_STREAM(args)
int main(int argc, char **argv)
Definition: RosAria.cpp:748
ros::ServiceServer disable_srv
Definition: RosAria.cpp:88
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
ros::Timer cmdvel_watchdog_timer
Definition: RosAria.cpp:93
ros::Publisher state_of_charge_pub
Definition: RosAria.cpp:79
ArFunctorC< RosAriaNode > myPublishCB
Definition: RosAria.cpp:105
bool disable_motors_cb(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Definition: RosAria.cpp:707
ros::Publisher recharge_state_pub
Definition: RosAria.cpp:76
bool getParam(const std::string &key, std::string &s) const
std::string frame_id_sonar
Definition: RosAria.cpp:115
ros::Publisher bumpers_pub
Definition: RosAria.cpp:71
#define ROS_FATAL_NAMED(name,...)
void cmdvel_watchdog(const ros::TimerEvent &event)
Definition: RosAria.cpp:733
virtual ~RosAriaNode()
Definition: RosAria.cpp:342
static Time now()
bool publish_sonar
Definition: RosAria.cpp:121
void sonarConnectCb()
Called when another node subscribes or unsubscribes from sonar topic.
Definition: RosAria.cpp:261
ros::Publisher motors_state_pub
Definition: RosAria.cpp:81
dynamic_reconfigure::Server< rosaria::RosAriaConfig > * dynamic_reconfigure_server
Definition: RosAria.cpp:132
#define ROS_ERROR(...)
ArRobotConnector * conn
Definition: RosAria.cpp:99
tf::TransformBroadcaster odom_broadcaster
Definition: RosAria.cpp:109
int RevCount
Definition: RosAria.cpp:129
#define ROS_DEBUG(...)


rosaria
Author(s): Srećko Jurić-Kavelj
autogenerated on Fri Jun 7 2019 22:02:02