$search
00001 /* 00002 * erratic_player 00003 * Copyright (c) 2010, Antons Rebguns. 00004 * Copyright (c) 2010, Pablo Inigo Blasco. RTC Group - Universidad de Sevilla. 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above copyright 00014 * notice, this list of conditions and the following disclaimer in the 00015 * documentation and/or other materials provided with the distribution. 00016 * * Neither the name of the <ORGANIZATION> nor the names of its 00017 * contributors may be used to endorse or promote products derived from 00018 * this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00021 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00022 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00023 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00024 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00025 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00026 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00027 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00028 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00029 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00030 * POSSIBILITY OF SUCH DAMAGE. 00031 */ 00032 00097 #include <assert.h> 00098 #include <boost/thread.hpp> 00099 #include <boost/lexical_cast.hpp> 00100 00101 // For core Player stuff (message queues, config file objects, etc.) 00102 #include <libplayercore/playercore.h> 00103 // TODO: remove XDR dependency 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 // Must prototype this function here. It's implemented inside 00121 // libplayerdrivers. 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"; // use robot's default value 00155 std::string trans_decel = trans_acc; 00156 std::string rot_acc = "0"; // use robot's default value 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 // libplayercore boiler plate 00181 player_globals_init(); 00182 itable_init(); 00183 00184 // TODO: remove XDR dependency 00185 playerxdr_ftable_init(); 00186 00187 //create publishers for odometry and battery information 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 // The Player address that will be assigned to this device. The format 00194 // is interface:index. The interface must match what the driver is 00195 // expecting to provide. The value of the index doesn't really matter, 00196 // but 0 is most common. 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 // Create a ConfigFile object, into which we'll stuff parameters. 00205 // Drivers assume that this object will persist throughout execution 00206 // (e.g., they store pointers to data inside it). So it must NOT be 00207 // deleted until after the driver is shut down. 00208 this->cf = new ConfigFile(); 00209 00210 // Insert (name,value) pairs into the ConfigFile object. These would 00211 // presumably come from the param server 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 // optional erratic accessories 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 // Create an instance of the driver, passing it the ConfigFile object. 00232 // The -1 tells it to look into the "global" section of the ConfigFile, 00233 // which is where ConfigFile::InsertFieldValue() put the parameters. 00234 assert((this->driver = Erratic_Init(cf, -1))); 00235 00236 // Print out warnings about parameters that were set, but which the 00237 // driver never looked at. 00238 cf->WarnUnused(); 00239 00240 // Grab from the global deviceTable a pointer to the Device that was 00241 // created as part of the driver's initialization. 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 // Create a message queue 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 // Subscribe to device, which causes it to startup 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 // Unsubscribe from the device, which causes it to shutdown 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 // Give the driver a chance to shutdown. Wish there were a way to 00342 // detect when that happened. 00343 usleep(1000000); 00344 return(status); 00345 } 00346 00347 int setMotorState(uint8_t state) 00348 { 00349 Message* msg; 00350 00351 // Enable the motors 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 //Wait until there is a message for geometry 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 if (fabs(msg.twist.twist.linear.x) <= 1e-8 && 00452 fabs(msg.twist.twist.linear.y) <= 1e-8 && 00453 fabs(msg.twist.twist.linear.z) <= 1e-8) 00454 { 00455 //nav_msgs::Odometry has a 6x6 covariance matrix 00456 msg.pose.covariance[0] = 1e-12; 00457 msg.pose.covariance[7] = 1e-12; 00458 msg.pose.covariance[35] = 1e-12; 00459 } 00460 else 00461 { 00462 // nav_msgs::Odometry has a 6x6 covariance matrix 00463 msg.pose.covariance[0] = pow(sigma_x_, 2); 00464 msg.pose.covariance[7] = pow(sigma_y_, 2); 00465 msg.pose.covariance[35] = pow(sigma_theta_, 2); 00466 } 00467 00468 msg.pose.covariance[14] = DBL_MAX; 00469 msg.pose.covariance[21] = DBL_MAX; 00470 msg.pose.covariance[28] = DBL_MAX; 00471 00472 msg.twist.covariance = msg.pose.covariance; 00473 } 00474 00475 void doUpdate() 00476 { 00477 Message* msg = NULL; 00478 00479 // Block until there's a message on the queue 00480 q->Wait(); 00481 00482 // Pop off one message (we own the resulting memory) 00483 if (!(msg = q->Pop())) 00484 { 00485 ROS_WARN("Empty message queue, no messages to pop."); 00486 return; 00487 } 00488 00489 // Is the message one we care about? 00490 player_msghdr_t* hdr = msg->GetHeader(); 00491 00492 if ((hdr->type == PLAYER_MSGTYPE_DATA) && 00493 (hdr->subtype == PLAYER_POSITION2D_DATA_STATE) && 00494 (hdr->addr.interf == PLAYER_POSITION2D_CODE)) 00495 { 00496 // Cast the message payload appropriately 00497 player_position2d_data_t* pdata = (player_position2d_data_t*) msg->GetPayload(); 00498 00499 nav_msgs::Odometry odom; 00500 00501 // Translate from Player data to ROS data 00502 odom.pose.pose.position.x = pdata->pos.px; 00503 odom.pose.pose.position.y = pdata->pos.py; 00504 odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(pdata->pos.pa); 00505 00506 odom.twist.twist.linear.x = pdata->vel.px; 00507 odom.twist.twist.linear.y = pdata->vel.py; 00508 odom.twist.twist.angular.z = pdata->vel.pa; 00509 00510 //@todo TODO: Think about publishing stall information with odometry or on a separate topic 00511 //odom.stall = pdata->stall; 00512 00513 odom.header.frame_id = tf::resolve(tf_prefix_, odom_frame_id); 00514 odom.header.stamp.sec = (long long unsigned int) floor(hdr->timestamp); 00515 odom.header.stamp.nsec = (long long unsigned int) ((hdr->timestamp - floor(hdr->timestamp)) * 1000000000ULL); 00516 00517 populateCovariance(odom); 00518 00519 // Publish the new data 00520 odom_pub_.publish(odom); 00521 00522 if (publish_tf_) 00523 { 00524 tf_.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(pdata->pos.pa), 00525 tf::Point(pdata->pos.px, 00526 pdata->pos.py, 00527 0.0)), 00528 ros::Time(odom.header.stamp.sec, odom.header.stamp.nsec), 00529 odom_frame_id, 00530 "base_footprint")); 00531 } 00532 00533 //printf("Published new odom: (%.3f,%.3f,%.3f)\n", 00534 //odom.pose.pose.position.x, odom.pose.pose.position.y, odom.pose.pose.position.th); 00535 } 00536 else if ((hdr->type == PLAYER_MSGTYPE_DATA) && 00537 (hdr->subtype == PLAYER_POWER_DATA_STATE) && 00538 (hdr->addr.interf == PLAYER_POWER_CODE)) 00539 { 00540 player_power_data_t* pdata = (player_power_data_t*) msg->GetPayload(); 00541 erratic_player::BatteryState state; 00542 00543 if (pdata->percent < 25) { ROS_WARN("Battery capacity is at %f%% (%fV), please recharge", pdata->percent, pdata->volts); } 00544 00545 state.header.stamp = ros::Time::now(); 00546 state.capacity = pdata->percent; 00547 state.charge = pdata->volts; 00548 00549 ROS_DEBUG("percent = %f, volts = %f", pdata->percent, pdata->volts); 00550 //state.time_remaining.fromSec((pdata->volts < 11.5) ? 0 : 3600); //need to calculate the remaing runtime based on the batteries discharge curve, for now stop when voltage is below 11.5. -Curt 00551 //state.power_consumption = (pdata->volts > charging_threshold_) ? watts_charging_ : watts_unplugged_; //Does not work, as they don't publish this 00552 //state.AC_present = (pdata->volts > charging_threshold_) ? 1 : 0; // are we charging? 00553 00554 battery_pub_.publish(state); 00555 } 00556 else if ((hdr->type == PLAYER_MSGTYPE_DATA) && 00557 (hdr->subtype == PLAYER_SONAR_DATA_RANGES) && 00558 (hdr->addr.interf == PLAYER_SONAR_CODE)) 00559 { 00560 //ROS_INFO("Received Sonar msg type-> %d",hdr->addr.interf); 00561 player_sonar_data_t* pdata = (player_sonar_data_t*) msg->GetPayload(); 00562 00563 erratic_player::RangeArray rangerArray; 00564 rangerArray.ranges.resize(pdata->ranges_count); 00565 00566 for (uint32_t i = 0 ; i < pdata->ranges_count; ++i) 00567 { 00568 //ROS_INFO("Sonar(%d) = %f m", i, pdata->ranges[i]); 00569 rangerArray.ranges[i].header.stamp = ros::Time::now(); 00570 rangerArray.ranges[i].header.frame_id = string("erratic_sonar_"); 00571 rangerArray.ranges[i].header.frame_id += boost::lexical_cast<std::string>(i); 00572 rangerArray.ranges[i].range = pdata->ranges[i]; 00573 00574 // 30 degrees following the erratic manual 00575 rangerArray.ranges[i].field_of_view = 0.5236085; 00576 rangerArray.ranges[i].max_range = 5; 00577 rangerArray.ranges[i].min_range = 0; 00578 rangerArray.ranges[i].radiation_type = sensor_msgs::Range::ULTRASOUND; 00579 } 00580 00581 sonar_pub.publish(rangerArray); 00582 } 00583 else if ((hdr->type == PLAYER_MSGTYPE_DATA) && 00584 (hdr->subtype == PLAYER_IR_DATA_RANGES) && 00585 (hdr->addr.interf == PLAYER_IR_CODE)) 00586 { 00587 player_ir_data_t* pdata = (player_ir_data_t*) msg->GetPayload(); 00588 00589 ros::Time timestamp = ros::Time::now(); 00590 erratic_player::RangeArray rangerArray; 00591 rangerArray.ranges.resize(pdata->ranges_count); 00592 00593 ROS_DEBUG("Received IR msg type, ranges_count -> %d, voltages_count: %d", pdata->ranges_count, pdata->voltages_count); 00594 // TODO: figure out why this segfaults 00595 00596 for (uint32_t i = 0 ; i < pdata->ranges_count; ++i) 00597 { 00598 rangerArray.ranges[i].header.stamp = timestamp; 00599 rangerArray.ranges[i].header.frame_id = string("erratic_ir_"); 00600 rangerArray.ranges[i].header.frame_id += boost::lexical_cast<std::string>(i); 00601 rangerArray.ranges[i].range = pdata->ranges[i]; 00602 rangerArray.ranges[i].radiation_type = sensor_msgs::Range::INFRARED; 00603 } 00604 00605 ir_pub_.publish(rangerArray); 00606 } 00607 else 00608 { 00609 ROS_WARN("Unhandled Player message %d:%d:%d:%d", 00610 hdr->type, 00611 hdr->subtype, 00612 hdr->addr.interf, 00613 hdr->addr.index); 00614 } 00615 00616 // We're done with the message now 00617 delete msg; 00618 } 00619 00620 private: 00621 double center_x_; 00622 double center_y_; 00623 double center_yaw_; 00624 00625 double watts_charging_; 00626 double watts_unplugged_; 00627 double charging_threshold_; 00628 00629 float vision_pan_rads; 00630 float vision_tilt_rads; 00631 00632 Driver* driver; 00633 Device* pos_device; 00634 Device* power_device; 00635 Device* sonar_device; 00636 Device* ir_device; 00637 Device* ranger_tilt_device; 00638 Device* vision_ptz_device; 00639 00640 ConfigFile* cf; 00641 std::string odom_frame_id; 00642 00643 bool enable_ir; 00644 bool enable_sonar; 00645 bool enable_ranger_tilt; 00646 bool enable_vision_pan_tilt; 00647 }; 00648 00649 void spinThread() 00650 { 00651 ros::spin(); 00652 } 00653 00654 int main(int argc, char** argv) 00655 { 00656 ros::init(argc, argv, "erratic_player"); 00657 00658 ErraticNode erratic; 00659 00660 ros::NodeHandle n; 00661 boost::thread spin_thread = boost::thread(boost::bind(&spinThread)); 00662 00663 // Start up the robot 00664 if (erratic.start() != 0) 00665 { 00666 exit(-1); 00667 } 00668 00669 // Enable the motors 00670 if (erratic.setMotorState(1) < 0) 00671 { 00672 ROS_ERROR("Failed to enable motors"); 00673 } 00674 00675 erratic.getCenter(); 00676 00678 // Main loop; grab messages off our queue and republish them via ROS 00679 while (n.ok()) 00680 { 00681 erratic.doUpdate(); 00682 } 00684 00685 // Stop the robot 00686 erratic.stop(); 00687 00688 spin_thread.join(); 00689 00690 // To quote Morgan, Hooray! 00691 return(0); 00692 }