00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00097 #include <assert.h>
00098 #include <boost/thread.hpp>
00099 #include <boost/lexical_cast.hpp>
00100
00101
00102 #include <libplayercore/playercore.h>
00103
00104 #include <libplayerxdr/playerxdr.h>
00105
00106 #include <ros/ros.h>
00107 #include <tf/transform_broadcaster.h>
00108 #include <tf/transform_listener.h>
00109
00110 #include <geometry_msgs/Twist.h>
00111 #include <nav_msgs/Odometry.h>
00112 #include <sensor_msgs/Range.h>
00113 #include <std_msgs/Float64.h>
00114
00115 #include <erratic_player/BatteryState.h>
00116 #include <erratic_player/RangeArray.h>
00117
00118 #define PLAYER_QUEUE_LEN 32
00119
00120
00121
00122 Driver* Erratic_Init(ConfigFile* cf, int section);
00123
00124 class ErraticNode
00125 {
00126 public:
00127 QueuePointer q;
00128 ros::NodeHandle node_;
00129
00130 tf::TransformBroadcaster tf_;
00131
00132 ros::Publisher odom_pub_;
00133 ros::Publisher battery_pub_;
00134 ros::Publisher ir_pub_;
00135 ros::Publisher sonar_pub;
00136 ros::Subscriber cmd_vel_sub_;
00137 ros::Subscriber cmd_ranger_tilt_sub_;
00138 ros::Subscriber cmd_vision_tilt_sub_;
00139 ros::Subscriber cmd_vision_pan_sub_;
00140 std::string tf_prefix_;
00141
00142 bool publish_tf_;
00143 double sigma_x_;
00144 double sigma_y_;
00145 double sigma_theta_;
00146
00147 ErraticNode() : watts_charging_(10), watts_unplugged_(-10), charging_threshold_(12.98)
00148 {
00149 ros::NodeHandle private_nh("~");
00150
00151 std::string port = "/dev/ttyUSB0";
00152 std::string max_trans_vel = "0.5";
00153 std::string max_rot_vel = "100";
00154 std::string trans_acc = "0";
00155 std::string trans_decel = trans_acc;
00156 std::string rot_acc = "0";
00157 std::string rot_decel = rot_acc;
00158
00159 private_nh.getParam("port_name", port);
00160 private_nh.getParam("max_trans_vel", max_trans_vel);
00161 private_nh.getParam("max_rot_vel", max_rot_vel);
00162 private_nh.getParam("trans_acc", trans_acc);
00163 private_nh.getParam("trans_decel", trans_decel);
00164 private_nh.getParam("rot_acc", rot_acc);
00165 private_nh.getParam("rot_decel", rot_decel);
00166
00167 private_nh.param("enable_ir", enable_ir, false);
00168 private_nh.param("enable_sonar", enable_sonar, false);
00169 private_nh.param("enable_vision_pan_tilt", enable_vision_pan_tilt, false);
00170 private_nh.param("enable_ranger_tilt", enable_ranger_tilt, false);
00171 private_nh.param("publish_tf", publish_tf_, true);
00172 private_nh.param("odometry_frame_id", odom_frame_id, string("odom"));
00173
00174 private_nh.param<double>("x_stddev", sigma_x_, 0.006);
00175 private_nh.param<double>("y_stddev", sigma_y_, 0.006);
00176 private_nh.param<double>("rotation_stddev", sigma_theta_, 0.051);
00177
00178 tf_prefix_ = tf::getPrefixParam(node_);
00179
00180
00181 player_globals_init();
00182 itable_init();
00183
00184
00185 playerxdr_ftable_init();
00186
00187
00188 odom_pub_ = node_.advertise<nav_msgs::Odometry>("odom", 1);
00189 battery_pub_ = node_.advertise<erratic_player::BatteryState>("battery_state", 1);
00190 if (enable_ir) { ir_pub_ = node_.advertise<erratic_player::RangeArray>("ir", 1); }
00191 if (enable_sonar) { sonar_pub = node_.advertise<erratic_player::RangeArray>("sonar",1); }
00192
00193
00194
00195
00196
00197 const char* player_addr_pos = "position2d:0";
00198 const char* player_addr_power = "power:0";
00199 const char* player_addr_ir = "ir:0";
00200 const char* player_addr_sonar="sonar:0";
00201 const char* player_addr_vision_ptz="ptz:0";
00202 const char* player_addr_ranger_tilt="tilt:::ptz:1";
00203
00204
00205
00206
00207
00208 this->cf = new ConfigFile();
00209
00210
00211
00212 int field_id = 0;
00213
00214 this->cf->InsertFieldValue(field_id++, "provides", player_addr_pos);
00215 this->cf->InsertFieldValue(field_id++, "provides", player_addr_power);
00216
00217
00218 if (enable_ir) { this->cf->InsertFieldValue(field_id++, "provides", player_addr_ir); }
00219 if (enable_sonar) {this->cf->InsertFieldValue(field_id++,"provides", player_addr_sonar);}
00220 if (enable_vision_pan_tilt) {this->cf->InsertFieldValue(field_id++,"provides", player_addr_vision_ptz);}
00221 if (enable_ranger_tilt) {this->cf->InsertFieldValue(field_id++,"provides", player_addr_ranger_tilt);}
00222
00223 this->cf->InsertFieldValue(0, "port", port.c_str());
00224 this->cf->InsertFieldValue(0, "max_trans_vel", max_trans_vel.c_str());
00225 this->cf->InsertFieldValue(0, "max_rot_vel", max_rot_vel.c_str());
00226 this->cf->InsertFieldValue(0, "trans_acc", trans_acc.c_str());
00227 this->cf->InsertFieldValue(0, "trans_decel", trans_decel.c_str());
00228 this->cf->InsertFieldValue(0, "rot_acc", rot_acc.c_str());
00229 this->cf->InsertFieldValue(0, "rot_decel", rot_decel.c_str());
00230
00231
00232
00233
00234 assert((this->driver = Erratic_Init(cf, -1)));
00235
00236
00237
00238 cf->WarnUnused();
00239
00240
00241
00242 assert((this->pos_device = deviceTable->GetDevice(player_addr_pos, false)));
00243 assert((this->power_device = deviceTable->GetDevice(player_addr_power, false)));
00244
00245 if (enable_ir) { assert((this->ir_device = deviceTable->GetDevice(player_addr_ir, false))); }
00246 if (enable_sonar) { assert((this->sonar_device = deviceTable->GetDevice(player_addr_sonar,false))); }
00247 if (enable_vision_pan_tilt) { assert((this->vision_ptz_device = deviceTable->GetDevice(player_addr_vision_ptz,false))); }
00248 if (enable_ranger_tilt) { assert((this->ranger_tilt_device = deviceTable->GetDevice(player_addr_ranger_tilt,false))); }
00249
00250
00251 this->q = QueuePointer(false, PLAYER_QUEUE_LEN);
00252 }
00253
00254 ~ErraticNode()
00255 {
00256 delete cf;
00257 player_globals_fini();
00258 }
00259
00260 int start()
00261 {
00262
00263 if (this->pos_device->Subscribe(this->q) != 0)
00264 {
00265 ROS_ERROR("Failed to start the odometry device");
00266 return(-1);
00267 }
00268
00269 if (this->power_device->Subscribe(this->q) != 0)
00270 {
00271 ROS_ERROR("Failed to start the power device");
00272 return(-1);
00273 }
00274
00275 if (enable_ir && (this->ir_device->Subscribe(this->q) != 0))
00276 {
00277 ROS_ERROR("Failed to start the ir device");
00278 return(-1);
00279 }
00280
00281 if (enable_sonar && (this->sonar_device->Subscribe(this->q) != 0))
00282 {
00283 ROS_ERROR("Failed to start the sonar device");
00284 return(-1);
00285 }
00286
00287 cmd_vel_sub_ = node_.subscribe<geometry_msgs::Twist>("cmd_vel", 1, boost::bind(&ErraticNode::cmdVelReceived, this, _1));
00288
00289 if (enable_vision_pan_tilt)
00290 {
00291 cmd_vision_pan_sub_ = node_.subscribe<std_msgs::Float64>("cmd_vision_pan", 1, boost::bind(&ErraticNode::cmdVisionPanReceived,this,_1));
00292 cmd_vision_tilt_sub_ = node_.subscribe<std_msgs::Float64>("cmd_vision_tilt", 1, boost::bind(&ErraticNode::cmdVisionTiltReceived,this,_1));
00293 }
00294
00295 if (enable_ranger_tilt) { cmd_ranger_tilt_sub_=node_.subscribe<std_msgs::Float64>("cmd_ranger_tilt", 1, boost::bind(&ErraticNode::cmdRangerTiltReceived,this,_1)); }
00296
00297 return(0);
00298 }
00299
00300 int stop()
00301 {
00302 int status = 0;
00303
00304
00305 if (this->pos_device->Unsubscribe(this->q) != 0)
00306 {
00307 ROS_WARN("Failed to stop the odometry device");
00308 status = -1;
00309 }
00310
00311 if (this->power_device->Unsubscribe(this->q) != 0)
00312 {
00313 ROS_WARN("Failed to stop the power device");
00314 status = -1;
00315 }
00316
00317 if (enable_ir && (this->ir_device->Unsubscribe(this->q) != 0))
00318 {
00319 ROS_WARN("Failed to stop the ir device");
00320 status = -1;
00321 }
00322
00323 if (enable_sonar && (this->sonar_device->Unsubscribe(this->q) != 0))
00324 {
00325 ROS_WARN("Failed to stop the sonar device");
00326 status = -1;
00327 }
00328
00329 if (enable_vision_pan_tilt && (this->vision_ptz_device->Unsubscribe(this->q) != 0))
00330 {
00331 ROS_WARN("Failed to stop the vision pan/tilt device");
00332 status = -1;
00333 }
00334
00335 if (enable_ranger_tilt && (this->ranger_tilt_device->Unsubscribe(this->q) != 0))
00336 {
00337 ROS_WARN("Failed to stop the ranger tilt device");
00338 status = -1;
00339 }
00340
00341
00342
00343 usleep(1000000);
00344 return(status);
00345 }
00346
00347 int setMotorState(uint8_t state)
00348 {
00349 Message* msg;
00350
00351
00352 player_position2d_power_config_t motorconfig;
00353 motorconfig.state = state;
00354
00355 if (!(msg = this->pos_device->Request(this->q,
00356 PLAYER_MSGTYPE_REQ,
00357 PLAYER_POSITION2D_REQ_MOTOR_POWER,
00358 (void*) &motorconfig,
00359 sizeof(motorconfig), NULL, false)))
00360 {
00361 return(-1);
00362 }
00363 else
00364 {
00365 delete msg;
00366 return(0);
00367 }
00368 }
00369
00370
00371 void getCenter()
00372 {
00373 Message* msg = NULL;
00374
00375
00376 while (!(msg = this->pos_device->Request(this->q, PLAYER_MSGTYPE_REQ,
00377 PLAYER_POSITION2D_REQ_GET_GEOM,
00378 NULL, 0, NULL, false)))
00379 {
00380 ROS_ERROR("No geom for the robot from player (yet). Waiting one second and trying again.");
00381 ros::Duration(1, 0).sleep();
00382 }
00383
00384 player_position2d_geom_t* geomconfig = (player_position2d_geom_t*) msg->GetPayload();
00385 center_x_ = geomconfig->pose.px;
00386 center_y_ = geomconfig->pose.py;
00387 center_yaw_ = geomconfig->pose.pyaw;
00388 ROS_INFO("Robot center at (%fm %fm), yaw %f radians. Width %fm, length %fm", center_x_, center_y_, center_yaw_, geomconfig->size.sw, geomconfig->size.sl);
00389 delete msg;
00390 }
00391
00392 void cmdRangerTiltReceived (const std_msgs::Float64::ConstPtr& tilt)
00393 {
00394 player_ptz_cmd req;
00395 memset(&req, 0, sizeof(req));
00396
00397 req.tilt=tilt->data;
00398
00399 this->ranger_tilt_device->PutMsg(this->q,
00400 PLAYER_MSGTYPE_CMD,
00401 PLAYER_PTZ_CMD_STATE,
00402 (void*) &req,
00403 sizeof(req),NULL);
00404 }
00405
00406 void updateVisionPanTilt()
00407 {
00408 player_ptz_cmd req;
00409 memset(&req, 0, sizeof(req));
00410
00411 req.pan = vision_pan_rads;
00412 req.tilt = vision_tilt_rads;
00413
00414 this->vision_ptz_device->PutMsg(this->q,
00415 PLAYER_MSGTYPE_CMD,
00416 PLAYER_PTZ_CMD_STATE,
00417 (void*) &req,
00418 sizeof(req),NULL);
00419 }
00420
00421 void cmdVisionTiltReceived(const std_msgs::Float64::ConstPtr& tilt)
00422 {
00423 vision_tilt_rads = tilt->data;
00424 updateVisionPanTilt();
00425 }
00426
00427 void cmdVisionPanReceived(const std_msgs::Float64::ConstPtr& pan)
00428 {
00429 vision_pan_rads = pan->data;
00430 updateVisionPanTilt();
00431 }
00432
00433 void cmdVelReceived(const geometry_msgs::Twist::ConstPtr& cmd_vel)
00434 {
00435 player_position2d_cmd_vel_t cmd;
00436 memset(&cmd, 0, sizeof(cmd));
00437
00438 cmd.vel.px = cmd_vel->linear.x;
00439 cmd.vel.py = 0.0;
00440 cmd.vel.pa = cmd_vel->angular.z;
00441 cmd.state = 1;
00442
00443 this->pos_device->PutMsg(this->q,
00444 PLAYER_MSGTYPE_CMD,
00445 PLAYER_POSITION2D_CMD_VEL,
00446 (void*) &cmd,sizeof(cmd), NULL);
00447 }
00448
00449 void populateCovariance(nav_msgs::Odometry &msg)
00450 {
00451
00452 msg.pose.covariance[0] = pow(sigma_x_, 2);
00453 msg.pose.covariance[7] = pow(sigma_y_, 2);
00454 msg.pose.covariance[35] = pow(sigma_theta_, 2);
00455
00456 msg.pose.covariance[14] = DBL_MAX;
00457 msg.pose.covariance[21] = DBL_MAX;
00458 msg.pose.covariance[28] = DBL_MAX;
00459
00460 msg.twist.covariance = msg.pose.covariance;
00461 }
00462
00463 void doUpdate()
00464 {
00465 Message* msg = NULL;
00466
00467
00468 q->Wait();
00469
00470
00471 if (!(msg = q->Pop()))
00472 {
00473 ROS_WARN("Empty message queue, no messages to pop.");
00474 return;
00475 }
00476
00477
00478 player_msghdr_t* hdr = msg->GetHeader();
00479
00480 if ((hdr->type == PLAYER_MSGTYPE_DATA) &&
00481 (hdr->subtype == PLAYER_POSITION2D_DATA_STATE) &&
00482 (hdr->addr.interf == PLAYER_POSITION2D_CODE))
00483 {
00484
00485 player_position2d_data_t* pdata = (player_position2d_data_t*) msg->GetPayload();
00486
00487 nav_msgs::Odometry odom;
00488
00489
00490 odom.pose.pose.position.x = pdata->pos.px;
00491 odom.pose.pose.position.y = pdata->pos.py;
00492 odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(pdata->pos.pa);
00493
00494 odom.twist.twist.linear.x = pdata->vel.px;
00495 odom.twist.twist.linear.y = pdata->vel.py;
00496 odom.twist.twist.angular.z = pdata->vel.pa;
00497
00498
00499
00500
00501 odom.header.frame_id = tf::resolve(tf_prefix_, odom_frame_id);
00502 odom.header.stamp.sec = (long long unsigned int) floor(hdr->timestamp);
00503 odom.header.stamp.nsec = (long long unsigned int) ((hdr->timestamp - floor(hdr->timestamp)) * 1000000000ULL);
00504
00505 populateCovariance(odom);
00506
00507
00508 odom_pub_.publish(odom);
00509
00510 if (publish_tf_)
00511 {
00512 tf_.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(pdata->pos.pa),
00513 tf::Point(pdata->pos.px,
00514 pdata->pos.py,
00515 0.0)),
00516 ros::Time(odom.header.stamp.sec, odom.header.stamp.nsec),
00517 odom_frame_id,
00518 "base_footprint"));
00519 }
00520
00521
00522
00523 }
00524 else if ((hdr->type == PLAYER_MSGTYPE_DATA) &&
00525 (hdr->subtype == PLAYER_POWER_DATA_STATE) &&
00526 (hdr->addr.interf == PLAYER_POWER_CODE))
00527 {
00528 player_power_data_t* pdata = (player_power_data_t*) msg->GetPayload();
00529 erratic_player::BatteryState state;
00530
00531 if (pdata->percent < 25) { ROS_WARN("Battery capacity is at %f%% (%fV), please recharge", pdata->percent, pdata->volts); }
00532
00533 state.header.stamp = ros::Time::now();
00534 state.capacity = pdata->percent;
00535 state.charge = pdata->volts;
00536
00537 ROS_DEBUG("percent = %f, volts = %f", pdata->percent, pdata->volts);
00538
00539
00540
00541
00542 battery_pub_.publish(state);
00543 }
00544 else if ((hdr->type == PLAYER_MSGTYPE_DATA) &&
00545 (hdr->subtype == PLAYER_SONAR_DATA_RANGES) &&
00546 (hdr->addr.interf == PLAYER_SONAR_CODE))
00547 {
00548
00549 player_sonar_data_t* pdata = (player_sonar_data_t*) msg->GetPayload();
00550
00551 erratic_player::RangeArray rangerArray;
00552 rangerArray.ranges.resize(pdata->ranges_count);
00553
00554 for (uint32_t i = 0 ; i < pdata->ranges_count; ++i)
00555 {
00556
00557 rangerArray.ranges[i].header.stamp = ros::Time::now();
00558 rangerArray.ranges[i].header.frame_id = string("erratic_sonar_");
00559 rangerArray.ranges[i].header.frame_id += boost::lexical_cast<std::string>(i);
00560 rangerArray.ranges[i].range = pdata->ranges[i];
00561
00562
00563 rangerArray.ranges[i].field_of_view = 0.5236085;
00564 rangerArray.ranges[i].max_range = 5;
00565 rangerArray.ranges[i].min_range = 0;
00566 rangerArray.ranges[i].radiation_type = sensor_msgs::Range::ULTRASOUND;
00567 }
00568
00569 sonar_pub.publish(rangerArray);
00570 }
00571 else if ((hdr->type == PLAYER_MSGTYPE_DATA) &&
00572 (hdr->subtype == PLAYER_IR_DATA_RANGES) &&
00573 (hdr->addr.interf == PLAYER_IR_CODE))
00574 {
00575 player_ir_data_t* pdata = (player_ir_data_t*) msg->GetPayload();
00576
00577 ros::Time timestamp = ros::Time::now();
00578 erratic_player::RangeArray rangerArray;
00579 rangerArray.ranges.resize(pdata->ranges_count);
00580
00581 ROS_DEBUG("Received IR msg type, ranges_count -> %d, voltages_count: %d", pdata->ranges_count, pdata->voltages_count);
00582
00583
00584 for (uint32_t i = 0 ; i < pdata->ranges_count; ++i)
00585 {
00586 rangerArray.ranges[i].header.stamp = timestamp;
00587 rangerArray.ranges[i].header.frame_id = string("erratic_ir_");
00588 rangerArray.ranges[i].header.frame_id += boost::lexical_cast<std::string>(i);
00589 rangerArray.ranges[i].range = pdata->ranges[i];
00590 rangerArray.ranges[i].radiation_type = sensor_msgs::Range::INFRARED;
00591 }
00592
00593 ir_pub_.publish(rangerArray);
00594 }
00595 else
00596 {
00597 ROS_WARN("Unhandled Player message %d:%d:%d:%d",
00598 hdr->type,
00599 hdr->subtype,
00600 hdr->addr.interf,
00601 hdr->addr.index);
00602 }
00603
00604
00605 delete msg;
00606 }
00607
00608 private:
00609 double center_x_;
00610 double center_y_;
00611 double center_yaw_;
00612
00613 double watts_charging_;
00614 double watts_unplugged_;
00615 double charging_threshold_;
00616
00617 float vision_pan_rads;
00618 float vision_tilt_rads;
00619
00620 Driver* driver;
00621 Device* pos_device;
00622 Device* power_device;
00623 Device* sonar_device;
00624 Device* ir_device;
00625 Device* ranger_tilt_device;
00626 Device* vision_ptz_device;
00627
00628 ConfigFile* cf;
00629 std::string odom_frame_id;
00630
00631 bool enable_ir;
00632 bool enable_sonar;
00633 bool enable_ranger_tilt;
00634 bool enable_vision_pan_tilt;
00635 };
00636
00637 void spinThread()
00638 {
00639 ros::spin();
00640 }
00641
00642 int main(int argc, char** argv)
00643 {
00644 ros::init(argc, argv, "erratic_player");
00645
00646 ErraticNode erratic;
00647
00648 ros::NodeHandle n;
00649 boost::thread spin_thread = boost::thread(boost::bind(&spinThread));
00650
00651
00652 if (erratic.start() != 0)
00653 {
00654 exit(-1);
00655 }
00656
00657
00658 if (erratic.setMotorState(1) < 0)
00659 {
00660 ROS_ERROR("Failed to enable motors");
00661 }
00662
00663 erratic.getCenter();
00664
00666
00667 while (n.ok())
00668 {
00669 erratic.doUpdate();
00670 }
00672
00673
00674 erratic.stop();
00675
00676 spin_thread.join();
00677
00678
00679 return(0);
00680 }