forked from amor-ros-pkg/rosaria
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathRosAria.cpp
655 lines (548 loc) · 21.6 KB
/
RosAria.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
#include <stdio.h>
#include <math.h>
#include <Aria.h>
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
#include "geometry_msgs/Pose.h"
#include "geometry_msgs/PoseStamped.h"
#include <sensor_msgs/PointCloud.h> //for sonar data
#include "nav_msgs/Odometry.h"
#include "rosaria/BumperState.h"
#include "tf/tf.h"
#include "tf/transform_listener.h" //for tf::getPrefixParam
#include <tf/transform_broadcaster.h>
#include "tf/transform_datatypes.h"
#include <dynamic_reconfigure/server.h>
#include <rosaria/RosAriaConfig.h>
#include "std_msgs/Float64.h"
#include "std_msgs/Float32.h"
#include "std_msgs/Int8.h"
#include "std_msgs/Bool.h"
#include "std_srvs/Empty.h"
#include <sstream>
/** @brief Node that interfaces between ROS and mobile robot base features via ARIA library.
RosAriaNode will use ARIA to connect to a robot controller (configure via
~port parameter), either direct serial connection or over the network. It
runs ARIA's robot communications cycle in a background thread, and
as part of that cycle (a sensor interpretation task which calls RosAriaNode::publish()),
it publishes various topics with newly received robot
data. It also sends velocity commands to the robot when received in the
cmd_vel topic, and handles dynamic_reconfigure and Service requests.
For more information about ARIA see
http://robots.mobilerobots.com/wiki/Aria.
RosAria uses the roscpp client library, see http://www.ros.org/wiki/roscpp for
information, tutorials and documentation.
*/
class RosAriaNode
{
public:
RosAriaNode(ros::NodeHandle n);
virtual ~RosAriaNode();
public:
int Setup();
void cmdvel_cb( const geometry_msgs::TwistConstPtr &);
//void cmd_enable_motors_cb();
//void cmd_disable_motors_cb();
void spin();
void publish();
void sonarConnectCb();
void dynamic_reconfigureCB(rosaria::RosAriaConfig &config, uint32_t level);
void readParameters();
protected:
ros::NodeHandle n;
ros::Publisher pose_pub;
ros::Publisher bumpers_pub;
ros::Publisher sonar_pub;
ros::Publisher voltage_pub;
ros::Publisher recharge_state_pub;
std_msgs::Int8 recharge_state;
ros::Publisher state_of_charge_pub;
ros::Publisher motors_state_pub;
std_msgs::Bool motors_state;
bool published_motors_state;
ros::Subscriber cmdvel_sub;
ros::ServiceServer enable_srv;
ros::ServiceServer disable_srv;
bool enable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
bool disable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
ros::Time veltime;
std::string serial_port;
int serial_baud;
ArRobotConnector *conn;
ArRobot *robot;
nav_msgs::Odometry position;
rosaria::BumperState bumpers;
ArPose pos;
ArFunctorC<RosAriaNode> myPublishCB;
//ArRobot::ChargeState batteryCharge;
//for odom->base_link transform
tf::TransformBroadcaster odom_broadcaster;
geometry_msgs::TransformStamped odom_trans;
//for resolving tf names.
std::string tf_prefix;
std::string frame_id_odom;
std::string frame_id_base_link;
std::string frame_id_bumper;
std::string frame_id_sonar;
//Sonar support
bool use_sonar; ///< enable and publish sonars if true
// Debug Aria
bool debug_aria;
std::string aria_log_filename;
/// Odometry Calibration Settings (see readParameters())
int TicksMM, DriftFactor, RevCount;
// dynamic_reconfigure
dynamic_reconfigure::Server<rosaria::RosAriaConfig> dynamic_reconfigure_server;
};
void RosAriaNode::readParameters()
{
// Robot Parameters
robot->lock();
ros::NodeHandle n_("~");
if (n_.hasParam("TicksMM"))
{
n_.getParam( "TicksMM", TicksMM);
ROS_INFO("Setting TicksMM from ROS Parameter: %d", TicksMM);
robot->comInt(93, TicksMM);
}
else
{
TicksMM = robot->getOrigRobotConfig()->getTicksMM();
n_.setParam( "RevCount", RevCount);
}
if (n_.hasParam("DriftFactor"))
{
n_.getParam( "DriftFactor", DriftFactor);
ROS_INFO("Setting DriftFactor from ROS Parameter: %d", DriftFactor);
robot->comInt(89, DriftFactor);
}
else
{
DriftFactor = robot->getOrigRobotConfig()->getDriftFactor();
n_.setParam( "RevCount", RevCount);
}
if (n_.hasParam("RevCount"))
{
n_.getParam( "RevCount", RevCount);
ROS_INFO("Setting RevCount from ROS Parameter: %d", RevCount);
robot->comInt(88, RevCount);
}
else
{
RevCount = robot->getOrigRobotConfig()->getRevCount();
n_.setParam( "RevCount", RevCount);
}
robot->unlock();
}
void RosAriaNode::dynamic_reconfigureCB(rosaria::RosAriaConfig &config, uint32_t level)
{
//
// Odometry Settings
//
robot->lock();
if(TicksMM != config.TicksMM and TicksMM > 0)
{
ROS_INFO("Setting TicksMM from Dynamic Reconfigure: %d -> %d ", TicksMM, config.TicksMM);
TicksMM = config.TicksMM;
robot->comInt(93, TicksMM);
}
if(DriftFactor != config.DriftFactor)
{
ROS_INFO("Setting DriftFactor from Dynamic Reconfigure: %d -> %d ", DriftFactor, config.DriftFactor);
DriftFactor = config.DriftFactor;
robot->comInt(89, DriftFactor);
}
if(RevCount != config.RevCount and RevCount > 0)
{
ROS_INFO("Setting RevCount from Dynamic Reconfigure: %d -> %d ", RevCount, config.RevCount);
RevCount = config.RevCount;
robot->comInt(88, RevCount);
}
//
// Acceleration Parameters
//
int value;
value = config.trans_accel * 1000;
if(value != robot->getTransAccel() and value > 0)
{
ROS_INFO("Setting TransAccel from Dynamic Reconfigure: %d", value);
robot->setTransAccel(value);
}
value = config.trans_decel * 1000;
if(value != robot->getTransDecel() and value > 0)
{
ROS_INFO("Setting TransDecel from Dynamic Reconfigure: %d", value);
robot->setTransDecel(value);
}
value = config.lat_accel * 1000;
if(value != robot->getLatAccel() and value > 0)
{
ROS_INFO("Setting LatAccel from Dynamic Reconfigure: %d", value);
if (robot->getAbsoluteMaxLatAccel() > 0 )
robot->setLatAccel(value);
}
value = config.lat_decel * 1000;
if(value != robot->getLatDecel() and value > 0)
{
ROS_INFO("Setting LatDecel from Dynamic Reconfigure: %d", value);
if (robot->getAbsoluteMaxLatDecel() > 0 )
robot->setLatDecel(value);
}
value = config.rot_accel * 180/M_PI;
if(value != robot->getRotAccel() and value > 0)
{
ROS_INFO("Setting RotAccel from Dynamic Reconfigure: %d", value);
robot->setRotAccel(value);
}
value = config.rot_decel * 180/M_PI;
if(value != robot->getRotDecel() and value > 0)
{
ROS_INFO("Setting RotDecel from Dynamic Reconfigure: %d", value);
robot->setRotDecel(value);
}
robot->unlock();
}
/// Called when another node subscribes or unsubscribes from sonar topic.
void RosAriaNode::sonarConnectCb()
{
robot->lock();
if (sonar_pub.getNumSubscribers() == 0)
{
robot->disableSonar();
use_sonar = false;
}
else
{
robot->enableSonar();
use_sonar = true;
}
robot->unlock();
}
RosAriaNode::RosAriaNode(ros::NodeHandle nh) :
myPublishCB(this, &RosAriaNode::publish), serial_port(""), serial_baud(0), use_sonar(false)
{
// read in config options
n = nh;
// port parameter
n.param( "port", serial_port, std::string("/dev/ttyUSB0") );
ROS_INFO( "RosAria: using port: [%s]", serial_port.c_str() );
n.param("baud", serial_baud, 0);
if(serial_baud != 0)
ROS_INFO("RosAria: using serial port baud rate %d", serial_baud);
// handle debugging more elegantly
n.param( "debug_aria", debug_aria, false ); // default not to debug
n.param( "aria_log_filename", aria_log_filename, std::string("Aria.log") );
// Figure out what frame_id's to use. if a tf_prefix param is specified,
// it will be added to the beginning of the frame_ids.
//
// e.g. rosrun ... _tf_prefix:=MyRobot (or equivalently using <param>s in
// roslaunch files)
// will result in the frame_ids being set to /MyRobot/odom etc,
// rather than /odom. This is useful for Multi Robot Systems.
// See ROS Wiki for further details.
tf_prefix = tf::getPrefixParam(n);
frame_id_odom = tf::resolve(tf_prefix, "odom");
frame_id_base_link = tf::resolve(tf_prefix, "base_link");
frame_id_bumper = tf::resolve(tf_prefix, "bumpers_frame");
frame_id_sonar = tf::resolve(tf_prefix, "sonar_frame");
// advertise services for data topics
// second argument to advertise() is queue size.
// other argmuments (optional) are callbacks, or a boolean "latch" flag (whether to send current data to new
// subscribers when they subscribe).
// See ros::NodeHandle API docs.
pose_pub = n.advertise<nav_msgs::Odometry>("pose",1000);
bumpers_pub = n.advertise<rosaria::BumperState>("bumper_state",1000);
sonar_pub = n.advertise<sensor_msgs::PointCloud>("sonar", 50,
boost::bind(&RosAriaNode::sonarConnectCb, this),
boost::bind(&RosAriaNode::sonarConnectCb, this));
voltage_pub = n.advertise<std_msgs::Float64>("battery_voltage", 1000);
recharge_state_pub = n.advertise<std_msgs::Int8>("battery_recharge_state", 5, true /*latch*/ );
recharge_state.data = -2;
state_of_charge_pub = n.advertise<std_msgs::Float32>("battery_state_of_charge", 100);
motors_state_pub = n.advertise<std_msgs::Bool>("motors_state", 5, true /*latch*/ );
motors_state.data = false;
published_motors_state = false;
// subscribe to services
cmdvel_sub = n.subscribe( "cmd_vel", 1, (boost::function <void(const geometry_msgs::TwistConstPtr&)>)
boost::bind(&RosAriaNode::cmdvel_cb, this, _1 ));
// advertise enable/disable services
enable_srv = n.advertiseService("enable_motors", &RosAriaNode::enable_motors_cb, this);
disable_srv = n.advertiseService("disable_motors", &RosAriaNode::disable_motors_cb, this);
veltime = ros::Time::now();
}
RosAriaNode::~RosAriaNode()
{
// disable motors and sonar.
robot->disableMotors();
robot->disableSonar();
robot->stopRunning();
robot->waitForRunExit();
Aria::shutdown();
}
int RosAriaNode::Setup()
{
// Note, various objects are allocated here which are never deleted (freed), since Setup() is only supposed to be
// called once per instance, and these objects need to persist until the process terminates.
robot = new ArRobot();
ArArgumentBuilder *args = new ArArgumentBuilder(); // never freed
ArArgumentParser *argparser = new ArArgumentParser(args); // Warning never freed
argparser->loadDefaultArguments(); // adds any arguments given in /etc/Aria.args. Useful on robots with unusual serial port or baud rate (e.g. pioneer lx)
// Now add any parameters given via ros params (see RosAriaNode constructor):
// if serial port parameter contains a ':' character, then interpret it as hostname:tcpport
// for wireless serial connection. Otherwise, interpret it as a serial port name.
size_t colon_pos = serial_port.find(":");
if (colon_pos != std::string::npos)
{
args->add("-remoteHost"); // pass robot's hostname/IP address to Aria
args->add(serial_port.substr(0, colon_pos).c_str());
args->add("-remoteRobotTcpPort"); // pass robot's TCP port to Aria
args->add(serial_port.substr(colon_pos+1).c_str());
}
else
{
args->add("-robotPort"); // pass robot's serial port to Aria
args->add(serial_port.c_str());
}
// if a baud rate was specified in baud parameter
if(serial_baud != 0)
{
args->add("-robotBaud");
char tmp[100];
snprintf(tmp, 100, "%d", serial_baud);
args->add(tmp);
}
if( debug_aria )
{
// turn on all ARIA debugging
args->add("-robotLogPacketsReceived"); // log received packets
args->add("-robotLogPacketsSent"); // log sent packets
args->add("-robotLogVelocitiesReceived"); // log received velocities
args->add("-robotLogMovementSent");
args->add("-robotLogMovementReceived");
ArLog::init(ArLog::File, ArLog::Verbose, aria_log_filename.c_str(), true);
}
// Connect to the robot
conn = new ArRobotConnector(argparser, robot); // warning never freed
if (!conn->connectRobot()) {
ROS_ERROR("RosAria: ARIA could not connect to robot! (Check ~port parameter is correct, and permissions on port device.)");
return 1;
}
// causes ARIA to load various robot-specific hardware parameters from the robot parameter file in /usr/local/Aria/params
if(!Aria::parseArgs())
{
ROS_ERROR("RosAria: ARIA error parsing ARIA startup parameters!");
return 1;
}
readParameters();
// start dynamic_reconfigure server
rosaria::RosAriaConfig dynConf_max;
dynConf_max.trans_accel = robot->getAbsoluteMaxTransAccel() / 1000;
dynConf_max.trans_decel = robot->getAbsoluteMaxTransDecel() / 1000;
// TODO: Fix rqt dynamic_reconfigure gui to handle empty intervals
// Until then, set unit length interval.
dynConf_max.lat_accel = ((robot->getAbsoluteMaxLatAccel() > 0.0) ? robot->getAbsoluteMaxLatAccel() : 0.1) / 1000;
dynConf_max.lat_decel = ((robot->getAbsoluteMaxLatDecel() > 0.0) ? robot->getAbsoluteMaxLatDecel() : 0.1) / 1000;
dynConf_max.rot_accel = robot->getAbsoluteMaxRotAccel() * M_PI/180;
dynConf_max.rot_decel = robot->getAbsoluteMaxRotDecel() * M_PI/180;
// I'm setting these upper bounds relitivly arbitrarily, feel free to increase them.
dynConf_max.TicksMM = 200;
dynConf_max.DriftFactor = 200;
dynConf_max.RevCount = 32760;
dynamic_reconfigure_server.setConfigMax(dynConf_max);
rosaria::RosAriaConfig dynConf_default;
dynConf_default.trans_accel = robot->getTransAccel() / 1000;
dynConf_default.trans_decel = robot->getTransDecel() / 1000;
dynConf_default.lat_accel = robot->getLatAccel() / 1000;
dynConf_default.lat_decel = robot->getLatDecel() / 1000;
dynConf_default.rot_accel = robot->getRotAccel() * M_PI/180;
dynConf_default.rot_decel = robot->getRotDecel() * M_PI/180;
dynConf_default.TicksMM = TicksMM;
dynConf_default.DriftFactor = DriftFactor;
dynConf_default.RevCount = RevCount;
dynamic_reconfigure_server.setConfigDefault(dynConf_max);
dynamic_reconfigure_server.setCallback(boost::bind(&RosAriaNode::dynamic_reconfigureCB, this, _1, _2));
// Enable the motors
robot->enableMotors();
// disable sonars on startup
robot->disableSonar();
// callback will be called by ArRobot background processing thread for every SIP data packet received from robot
robot->addSensorInterpTask("ROSPublishingTask", 100, &myPublishCB);
// Initialize bumpers with robot number of bumpers
bumpers.front_bumpers.resize(robot->getNumFrontBumpers());
bumpers.rear_bumpers.resize(robot->getNumRearBumpers());
// Run ArRobot background processing thread
robot->runAsync(true);
return 0;
}
void RosAriaNode::spin()
{
ros::spin();
}
void RosAriaNode::publish()
{
// Note, this is called via SensorInterpTask callback (myPublishCB, named "ROSPublishingTask"). ArRobot object 'robot' sholud not be locked or unlocked.
pos = robot->getPose();
tf::poseTFToMsg(tf::Transform(tf::createQuaternionFromYaw(pos.getTh()*M_PI/180), tf::Vector3(pos.getX()/1000,
pos.getY()/1000, 0)), position.pose.pose); //Aria returns pose in mm.
position.twist.twist.linear.x = robot->getVel()/1000.0; //Aria returns velocity in mm/s.
position.twist.twist.linear.y = robot->getLatVel()/1000.0;
position.twist.twist.angular.z = robot->getRotVel()*M_PI/180;
position.header.frame_id = frame_id_odom;
position.child_frame_id = frame_id_base_link;
position.header.stamp = ros::Time::now();
pose_pub.publish(position);
ROS_DEBUG("RosAria: publish vel: (time %f) linear x: %f, y: %f; angular z: %f",
position.header.stamp.toSec(),
(double) position.twist.twist.linear.x,
(double) position.twist.twist.linear.y,
(double) position.twist.twist.angular.z
);
// publishing transform odom->base_link
odom_trans.header.stamp = ros::Time::now();
odom_trans.header.frame_id = frame_id_odom;
odom_trans.child_frame_id = frame_id_base_link;
odom_trans.transform.translation.x = pos.getX()/1000;
odom_trans.transform.translation.y = pos.getY()/1000;
odom_trans.transform.translation.z = 0.0;
odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(pos.getTh()*M_PI/180);
odom_broadcaster.sendTransform(odom_trans);
// getStallValue returns 2 bytes with stall bit and bumper bits, packed as (00 00 FrontBumpers RearBumpers)
int stall = robot->getStallValue();
unsigned char front_bumpers = (unsigned char)(stall >> 8);
unsigned char rear_bumpers = (unsigned char)(stall);
bumpers.header.frame_id = frame_id_bumper;
bumpers.header.stamp = ros::Time::now();
std::stringstream bumper_info(std::stringstream::out);
// Bit 0 is for stall, next bits are for bumpers (leftmost is LSB)
for (unsigned int i=0; i<robot->getNumFrontBumpers(); i++)
{
bumpers.front_bumpers[i] = (front_bumpers & (1 << (i+1))) == 0 ? 0 : 1;
bumper_info << " " << (front_bumpers & (1 << (i+1)));
}
ROS_DEBUG("RosAria: Front bumpers:%s", bumper_info.str().c_str());
bumper_info.str("");
// Rear bumpers have reverse order (rightmost is LSB)
unsigned int numRearBumpers = robot->getNumRearBumpers();
for (unsigned int i=0; i<numRearBumpers; i++)
{
bumpers.rear_bumpers[i] = (rear_bumpers & (1 << (numRearBumpers-i))) == 0 ? 0 : 1;
bumper_info << " " << (rear_bumpers & (1 << (numRearBumpers-i)));
}
ROS_DEBUG("RosAria: Rear bumpers:%s", bumper_info.str().c_str());
bumpers_pub.publish(bumpers);
//Publish battery information
// TODO: Decide if BatteryVoltageNow (normalized to (0,12)V) is a better option
std_msgs::Float64 batteryVoltage;
batteryVoltage.data = robot->getRealBatteryVoltageNow();
voltage_pub.publish(batteryVoltage);
if(robot->haveStateOfCharge())
{
std_msgs::Float32 soc;
soc.data = robot->getStateOfCharge()/100.0;
state_of_charge_pub.publish(soc);
}
// publish recharge state if changed
char s = robot->getChargeState();
if(s != recharge_state.data)
{
ROS_INFO("RosAria: publishing new recharge state %d.", s);
recharge_state.data = s;
recharge_state_pub.publish(recharge_state);
}
// publish motors state if changed
bool e = robot->areMotorsEnabled();
if(e != motors_state.data || !published_motors_state)
{
ROS_INFO("RosAria: publishing new motors state %d.", e);
motors_state.data = e;
motors_state_pub.publish(motors_state);
published_motors_state = true;
}
// Publish sonar information, if enabled.
if (use_sonar) {
sensor_msgs::PointCloud cloud; //sonar readings.
cloud.header.stamp = position.header.stamp; //copy time.
// sonar sensors relative to base_link
cloud.header.frame_id = frame_id_sonar;
// Log debugging info
std::stringstream sonar_debug_info;
sonar_debug_info << "Sonar readings: ";
for (int i = 0; i < robot->getNumSonar(); i++) {
ArSensorReading* reading = NULL;
reading = robot->getSonarReading(i);
if(!reading) {
ROS_WARN("RosAria: Did not receive a sonar reading.");
continue;
}
// getRange() will return an integer between 0 and 5000 (5m)
sonar_debug_info << reading->getRange() << " ";
// local (x,y). Appears to be from the centre of the robot, since values may
// exceed 5000. This is good, since it means we only need 1 transform.
// x & y seem to be swapped though, i.e. if the robot is driving north
// x is north/south and y is east/west.
//
//ArPose sensor = reading->getSensorPosition(); //position of sensor.
// sonar_debug_info << "(" << reading->getLocalX()
// << ", " << reading->getLocalY()
// << ") from (" << sensor.getX() << ", "
// << sensor.getY() << ") ;; " ;
//add sonar readings (robot-local coordinate frame) to cloud
geometry_msgs::Point32 p;
p.x = reading->getLocalX() / 1000.0;
p.y = reading->getLocalY() / 1000.0;
p.z = 0.0;
cloud.points.push_back(p);
}
ROS_DEBUG_STREAM(sonar_debug_info.str());
sonar_pub.publish(cloud);
}
}
bool RosAriaNode::enable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
{
ROS_INFO("RosAria: Enable motors request.");
robot->lock();
if(robot->isEStopPressed())
ROS_WARN("RosAria: Warning: Enable motors requested, but robot also has E-Stop button pressed. Motors will not enable.");
robot->enableMotors();
robot->unlock();
// todo could wait and see if motors do become enabled, and send a response with an error flag if not
return true;
}
bool RosAriaNode::disable_motors_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
{
ROS_INFO("RosAria: Disable motors request.");
robot->lock();
robot->disableMotors();
robot->unlock();
// todo could wait and see if motors do become disabled, and send a response with an error flag if not
return true;
}
void
RosAriaNode::cmdvel_cb( const geometry_msgs::TwistConstPtr &msg)
{
veltime = ros::Time::now();
ROS_INFO( "new speed: [%0.2f,%0.2f](%0.3f)", msg->linear.x*1e3, msg->angular.z, veltime.toSec() );
robot->lock();
robot->setVel(msg->linear.x*1e3);
robot->setLatVel(msg->linear.y*1e3);
robot->setRotVel(msg->angular.z*180/M_PI);
robot->unlock();
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(),
(double) msg->linear.x * 1e3, (double) msg->linear.y * 1.3, (double) msg->angular.z * 180/M_PI);
}
int main( int argc, char** argv )
{
ros::init(argc,argv, "RosAria");
ros::NodeHandle n(std::string("~"));
Aria::init();
RosAriaNode *node = new RosAriaNode(n);
if( node->Setup() != 0 )
{
ROS_FATAL( "RosAria: ROS node setup failed... \n" );
return -1;
}
node->spin();
delete node;
ROS_INFO( "RosAria: Quitting... \n" );
return 0;
}