00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <uwsim/ROSInterface.h>
00014 #include <uwsim/UWSimUtils.h>
00015 #include <osg/LineWidth>
00016 #include <osg/Material>
00017 #include <osgOcean/ShaderManager>
00018
00019 #include <sensor_msgs/Imu.h>
00020 #include <sensor_msgs/NavSatFix.h>
00021 #include <sensor_msgs/LaserScan.h>
00022 #include <underwater_sensor_msgs/Pressure.h>
00023 #include <underwater_sensor_msgs/DVL.h>
00024 #include <std_msgs/Bool.h>
00025 #include <osg/LineStipple>
00026 #include <robot_state_publisher/robot_state_publisher.h>
00027 #include <kdl_parser/kdl_parser.hpp>
00028
00029
00030 ros::Time ROSInterface::current_time_;
00031
00032 ROSSubscriberInterface::ROSSubscriberInterface(std::string topic) :
00033 ROSInterface(topic)
00034 {
00035 startThread();
00036 }
00037
00038
00039 void ROSSubscriberInterface::run()
00040 {
00041 ros::Duration(2).sleep();
00042 createSubscriber (nh_);
00043 }
00044
00045 ROSSubscriberInterface::~ROSSubscriberInterface()
00046 {
00047 join();
00048 }
00049
00050 ROSOdomToPAT::ROSOdomToPAT(osg::Group *rootNode, std::string topic, std::string vehicleName) :
00051 ROSSubscriberInterface(topic)
00052 {
00053 findNodeVisitor findNode(vehicleName);
00054 rootNode->accept(findNode);
00055 osg::Node *first = findNode.getFirst();
00056 if (first == NULL)
00057 {
00058 transform = NULL;
00059 }
00060 else
00061 {
00062 transform = dynamic_cast<osg::MatrixTransform*>(first);
00063 }
00064 started = 0;
00065 }
00066
00067 void ROSOdomToPAT::createSubscriber(ros::NodeHandle &nh)
00068 {
00069 ROS_INFO("ROSOdomToPAT subscriber on topic %s", topic.c_str());
00070 sub_ = nh.subscribe < nav_msgs::Odometry > (topic, 10, &ROSOdomToPAT::processData, this);
00071 if (sub_ == ros::Subscriber())
00072 {
00073 ROS_ERROR("ROSOdomToPAT::createSubscriber cannot subscribe to topic %s", topic.c_str());
00074 }
00075 }
00076
00077 void ROSOdomToPAT::processData(const nav_msgs::Odometry::ConstPtr& odom)
00078 {
00079 if (transform != NULL)
00080 {
00081
00082 osg::Matrixd sMsv_osg;
00083
00084
00085 if (odom->pose.pose.orientation.x != 0 || odom->pose.pose.orientation.y != 0 || odom->pose.pose.orientation.z != 0
00086 || odom->pose.pose.position.x != 0 || odom->pose.pose.position.y != 0 || odom->pose.pose.position.z != 0)
00087 {
00088 sMsv_osg.setTrans(odom->pose.pose.position.x, odom->pose.pose.position.y, odom->pose.pose.position.z);
00089 sMsv_osg.setRotate(
00090 osg::Quat(odom->pose.pose.orientation.x, odom->pose.pose.orientation.y, odom->pose.pose.orientation.z,
00091 odom->pose.pose.orientation.w));
00092 }
00093 else
00094 {
00095
00096 sMsv_osg = transform->getMatrix();
00097
00098
00099 double elapsed = 0;
00100 if (started != 0)
00101 {
00102 ros::WallDuration t_diff = ros::WallTime::now() - last;
00103 elapsed = t_diff.toSec();
00104
00105 if (elapsed > 1)
00106 elapsed = 0;
00107 }
00108 started = 1;
00109 last = ros::WallTime::now();
00110
00111
00112 osg::Matrixd vMnv;
00113 osg::Matrixd T, Rx, Ry, Rz;
00114 T.makeTranslate(odom->twist.twist.linear.x * elapsed, odom->twist.twist.linear.y * elapsed,
00115 odom->twist.twist.linear.z * elapsed);
00116 Rx.makeRotate(odom->twist.twist.angular.x * elapsed, 1, 0, 0);
00117 Ry.makeRotate(odom->twist.twist.angular.y * elapsed, 0, 1, 0);
00118 Rz.makeRotate(odom->twist.twist.angular.z * elapsed, 0, 0, 1);
00119 vMnv = Rz * Ry * Rx * T;
00120
00121 sMsv_osg = vMnv * sMsv_osg;
00122 }
00123 transform->setMatrix(sMsv_osg);
00124 }
00125 }
00126
00127 ROSOdomToPAT::~ROSOdomToPAT()
00128 {
00129 }
00130
00131 ROSTwistToPAT::ROSTwistToPAT(osg::Group *rootNode, std::string topic, std::string vehicleName) :
00132 ROSSubscriberInterface(topic)
00133 {
00134 findNodeVisitor findNode(vehicleName);
00135 rootNode->accept(findNode);
00136 osg::Node *first = findNode.getFirst();
00137 if (first == NULL)
00138 {
00139 transform = NULL;
00140 }
00141 else
00142 {
00143 transform = dynamic_cast<osg::MatrixTransform*>(first);
00144 }
00145 started = 0;
00146 }
00147
00148 void ROSTwistToPAT::createSubscriber(ros::NodeHandle &nh)
00149 {
00150 ROS_INFO("ROSTwistToPAT subscriber on topic %s", topic.c_str());
00151 sub_ = nh.subscribe < geometry_msgs::TwistStamped > (topic, 10, &ROSTwistToPAT::processData, this);
00152 }
00153
00154 void ROSTwistToPAT::processData(const geometry_msgs::TwistStamped::ConstPtr& twist)
00155 {
00156 if (transform != NULL)
00157 {
00158
00159 osg::Matrixd sMsv_osg;
00160
00161 sMsv_osg = transform->getMatrix();
00162
00163
00164 double elapsed = 0;
00165 if (started != 0)
00166 {
00167 ros::WallDuration t_diff = ros::WallTime::now() - last;
00168 elapsed = t_diff.toSec();
00169
00170 if (elapsed > 1)
00171 elapsed = 0;
00172 }
00173 started = 1;
00174 last = ros::WallTime::now();
00175
00176 osg::Matrixd vMnv;
00177 osg::Matrixd T, Rx, Ry, Rz;
00178 T.makeTranslate(twist->twist.linear.x * elapsed, twist->twist.linear.y * elapsed, twist->twist.linear.z * elapsed);
00179 Rx.makeRotate(twist->twist.angular.x * elapsed, 1, 0, 0);
00180 Ry.makeRotate(twist->twist.angular.y * elapsed, 0, 1, 0);
00181 Rz.makeRotate(twist->twist.angular.z * elapsed, 0, 0, 1);
00182 vMnv = Rz * Ry * Rx * T;
00183
00184 sMsv_osg = vMnv * sMsv_osg;
00185
00186 transform->setMatrix(sMsv_osg);
00187 }
00188 }
00189
00190 ROSTwistToPAT::~ROSTwistToPAT()
00191 {
00192 }
00193
00194 ROSPoseToPAT::ROSPoseToPAT(osg::Group *rootNode, std::string topic, std::string vehicleName) :
00195 ROSSubscriberInterface(topic)
00196 {
00197 findNodeVisitor findNode(vehicleName);
00198 rootNode->accept(findNode);
00199 osg::Node *first = findNode.getFirst();
00200 if (first == NULL)
00201 {
00202 transform = NULL;
00203 }
00204 else
00205 {
00206 transform = dynamic_cast<osg::MatrixTransform*>(first);
00207 }
00208 }
00209
00210 void ROSPoseToPAT::createSubscriber(ros::NodeHandle &nh)
00211 {
00212 ROS_INFO("ROSPoseToPAT subscriber on topic %s", topic.c_str());
00213 sub_ = nh.subscribe < geometry_msgs::Pose > (topic, 10, &ROSPoseToPAT::processData, this);
00214 }
00215
00216 void ROSPoseToPAT::processData(const geometry_msgs::Pose::ConstPtr& pose)
00217 {
00218 if (transform != NULL)
00219 {
00220
00221 osg::Matrixd sMsv_osg;
00222
00223 sMsv_osg.setTrans(pose->position.x, pose->position.y, pose->position.z);
00224 sMsv_osg.setRotate(osg::Quat(pose->orientation.x, pose->orientation.y, pose->orientation.z, pose->orientation.w));
00225
00226 transform->setMatrix(sMsv_osg);
00227
00228 }
00229 }
00230
00231 ROSPoseToPAT::~ROSPoseToPAT()
00232 {
00233 }
00234
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287 ROSJointStateToArm::ROSJointStateToArm(std::string topic, boost::shared_ptr<SimulatedIAUV> arm) :
00288 ROSSubscriberInterface(topic)
00289 {
00290 this->arm = arm;
00291 }
00292
00293 void ROSJointStateToArm::createSubscriber(ros::NodeHandle &nh)
00294 {
00295 ROS_INFO("ROSJointStateToArm subscriber on topic %s", topic.c_str());
00296 sub_ = nh.subscribe < sensor_msgs::JointState > (topic, 10, &ROSJointStateToArm::processData, this);
00297 }
00298
00299 void ROSJointStateToArm::processData(const sensor_msgs::JointState::ConstPtr& js)
00300 {
00301
00302 if (js->position.size() != 0)
00303 {
00304
00305 std::vector < std::string > names = js->name;
00306 std::vector<double> position = js->position;
00307 arm->urdf->setJointPosition(position, names);
00308 }
00309 else if (js->velocity.size() != 0)
00310 {
00311
00312 std::vector < std::string > names = js->name;
00313 std::vector<double> velocity = js->velocity;
00314 arm->urdf->setJointVelocity(velocity, names);
00315 }
00316 }
00317
00318 ROSJointStateToArm::~ROSJointStateToArm()
00319 {
00320 }
00321
00322 ROSImageToHUDCamera::ROSImageToHUDCamera(std::string topic, std::string info_topic, boost::shared_ptr<HUDCamera> camera) :
00323 ROSSubscriberInterface(info_topic), cam(camera), image_topic(topic)
00324 {
00325 }
00326
00327 void ROSImageToHUDCamera::createSubscriber(ros::NodeHandle &nh)
00328 {
00329 ROS_INFO("ROSImageToHUDCamera subscriber on topic %s", topic.c_str());
00330 it.reset(new image_transport::ImageTransport(nh));
00331 OSG_DEBUG << "ROSImageToHUDCamera::createSubscriber Subscribing to image topic " << image_topic << std::endl;
00332 image_sub = it->subscribe(image_topic, 1, &ROSImageToHUDCamera::processData, this);
00333
00334
00335 }
00336
00337 void ROSImageToHUDCamera::processData(const sensor_msgs::ImageConstPtr& msg)
00338 {
00339 OSG_DEBUG << "ROSImageToHUDCamera::imageCallback start: " << msg->width << "x" << msg->height << " step:" << msg->step
00340 << std::endl;
00341
00342
00343
00344 char *osgimage_data = (char*)cam->osg_image->data();
00345
00346
00347
00348 for (unsigned int i = 0; i < msg->height; i++)
00349 {
00350 for (unsigned int j = 0; j < msg->step; j++)
00351 {
00352 osgimage_data[i * msg->step + j] = msg->data[(msg->height - i - 1) * msg->step + j];
00353 }
00354 }
00355 cam->ready_ = true;
00356 OSG_DEBUG << "ROSImageToHUDCamera::imageCallback exit" << std::endl;
00357 }
00358
00359 ROSImageToHUDCamera::~ROSImageToHUDCamera()
00360 {
00361 }
00362
00363 ROSPublisherInterface::ROSPublisherInterface(std::string topic, int publish_rate) :
00364 ROSInterface(topic)
00365 {
00366 this->publish_rate = publish_rate;
00367 OSG_DEBUG << "ROSPublisherInterface Thread starting..." << topic << std::endl;
00368 startThread();
00369 OSG_DEBUG << "ROSPublisherInterface Thread created" << std::endl;
00370 }
00371
00372
00373 void ROSPublisherInterface::run()
00374 {
00375 ros::Duration(2).sleep();
00376 createPublisher (nh_);
00377
00378 ros::Rate rate(publish_rate);
00379 while (ros::ok())
00380 {
00381 publish();
00382
00383 rate.sleep();
00384 }
00385 }
00386
00387 ROSPublisherInterface::~ROSPublisherInterface()
00388 {
00389 join();
00390 }
00391
00392 PATToROSOdom::PATToROSOdom(osg::Group *rootNode, std::string vehicleName, std::string topic, int rate) :
00393 ROSPublisherInterface(topic, rate)
00394 {
00395
00396 findNodeVisitor findNode(vehicleName);
00397 rootNode->accept(findNode);
00398 osg::Node *first = findNode.getFirst();
00399 if (first == NULL)
00400 {
00401 transform = NULL;
00402 }
00403 else
00404 {
00405 transform = dynamic_cast<osg::MatrixTransform*>(first);
00406 }
00407 }
00408
00409 void PATToROSOdom::createPublisher(ros::NodeHandle &nh)
00410 {
00411 ROS_INFO("PATToROSOdom publisher on topic %s", topic.c_str());
00412 pub_ = nh.advertise < nav_msgs::Odometry > (topic, 1);
00413 }
00414
00415 void PATToROSOdom::publish()
00416 {
00417 if (transform != NULL)
00418 {
00419 nav_msgs::Odometry odom;
00420 odom.header.stamp = getROSTime();
00421
00422 osg::Matrixd mat = transform->getMatrix();
00423 osg::Vec3d pos = mat.getTrans();
00424 osg::Quat rot = mat.getRotate();
00425
00426 odom.pose.pose.position.x = pos.x();
00427 odom.pose.pose.position.y = pos.y();
00428 odom.pose.pose.position.z = pos.z();
00429 odom.pose.pose.orientation.x = rot.x();
00430 odom.pose.pose.orientation.y = rot.y();
00431 odom.pose.pose.orientation.z = rot.z();
00432 odom.pose.pose.orientation.w = rot.w();
00433
00434
00435 odom.twist.twist.linear.x = 0;
00436 odom.twist.twist.linear.y = 0;
00437 odom.twist.twist.linear.z = 0;
00438 odom.twist.twist.angular.x = 0;
00439 odom.twist.twist.angular.y = 0;
00440 odom.twist.twist.angular.z = 0;
00441 for (int i = 0; i < 36; i++)
00442 {
00443 odom.twist.covariance[i] = 0;
00444 odom.pose.covariance[i] = 0;
00445 }
00446
00447 pub_.publish(odom);
00448 }
00449 }
00450
00451 PATToROSOdom::~PATToROSOdom()
00452 {
00453 }
00454
00455 ImuToROSImu::ImuToROSImu(InertialMeasurementUnit *imu, std::string topic, int rate) :
00456 ROSPublisherInterface(topic, rate), imu_(imu)
00457 {
00458 }
00459
00460 void ImuToROSImu::createPublisher(ros::NodeHandle &nh)
00461 {
00462 ROS_INFO("Imu publisher on topic %s", topic.c_str());
00463 pub_ = nh.advertise < sensor_msgs::Imu > (topic, 1);
00464 }
00465
00466 void ImuToROSImu::publish()
00467 {
00468 if (imu_ != NULL)
00469 {
00470 osg::Quat rot = imu_->getMeasurement();
00471
00472 sensor_msgs::Imu imu;
00473 imu.header.stamp = getROSTime();
00474 imu.header.frame_id = "world";
00475 imu.orientation.x = rot.x();
00476 imu.orientation.y = rot.y();
00477 imu.orientation.z = rot.z();
00478 imu.orientation.w = rot.w();
00479
00480 imu.orientation_covariance[0] = imu.orientation_covariance[4] = imu.orientation_covariance[8] = std::pow(
00481 imu_->getStandardDeviation(), 2);
00482
00483 pub_.publish(imu);
00484 }
00485 }
00486
00487 ImuToROSImu::~ImuToROSImu()
00488 {
00489 }
00490
00491 PressureSensorToROS::PressureSensorToROS(PressureSensor *sensor, std::string topic, int rate) :
00492 ROSPublisherInterface(topic, rate), sensor_(sensor)
00493 {
00494 }
00495
00496 void PressureSensorToROS::createPublisher(ros::NodeHandle &nh)
00497 {
00498 ROS_INFO("PressureSensor publisher on topic %s", topic.c_str());
00499 pub_ = nh.advertise < underwater_sensor_msgs::Pressure > (topic, 1);
00500 }
00501
00502 void PressureSensorToROS::publish()
00503 {
00504 if (sensor_ != NULL)
00505 {
00506 double pressure = sensor_->getMeasurement();
00507
00508 underwater_sensor_msgs::Pressure v;
00509 v.pressure = pressure;
00510 v.header.stamp = getROSTime();
00511 v.header.frame_id = "world";
00512
00513 pub_.publish(v);
00514 }
00515 }
00516
00517 PressureSensorToROS::~PressureSensorToROS()
00518 {
00519 }
00520
00521 void GPSSensorToROS::createPublisher(ros::NodeHandle &nh)
00522 {
00523 ROS_INFO("GPSSensor publisher on topic %s", topic.c_str());
00524 pub_ = nh.advertise < sensor_msgs::NavSatFix > (topic, 1);
00525 }
00526
00527 void GPSSensorToROS::publish()
00528 {
00529 if (sensor_ != NULL)
00530 {
00531 osg::Vec3d wTgps = sensor_->getMeasurement();
00532
00533
00534 if (sensor_->depthBelowWater() < 0.5)
00535 {
00536 sensor_msgs::NavSatFix m;
00537 m.latitude = wTgps[0];
00538 m.longitude = wTgps[1];
00539 m.position_covariance[0] = m.position_covariance[4] = m.position_covariance[8] = std::pow(
00540 sensor_->getStandardDeviation(), 2);
00541 m.position_covariance_type = m.COVARIANCE_TYPE_DIAGONAL_KNOWN;
00542
00543 pub_.publish(m);
00544 }
00545 }
00546 }
00547
00548 void DVLSensorToROS::createPublisher(ros::NodeHandle &nh)
00549 {
00550 ROS_INFO("DVLSensor publisher on topic %s", topic.c_str());
00551 pub_ = nh.advertise < underwater_sensor_msgs::DVL > (topic, 1);
00552 }
00553
00554 void DVLSensorToROS::publish()
00555 {
00556 if (sensor_ != NULL)
00557 {
00558 osg::Vec3d vdvl = sensor_->getMeasurement();
00559
00560 underwater_sensor_msgs::DVL m;
00561 m.bi_x_axis = vdvl.x();
00562 m.bi_y_axis = vdvl.y();
00563 m.bi_z_axis = vdvl.z();
00564
00565 pub_.publish(m);
00566 }
00567 }
00568
00569 ArmToROSJointState::ArmToROSJointState(SimulatedIAUV *arm, std::string topic, int rate) :
00570 ROSPublisherInterface(topic, rate)
00571 {
00572 this->arm = arm->urdf;
00573 }
00574
00575 void ArmToROSJointState::createPublisher(ros::NodeHandle &nh)
00576 {
00577 ROS_INFO("ArmToROSJointState publisher on topic %s", topic.c_str());
00578 pub_ = nh.advertise < sensor_msgs::JointState > (topic, 1);
00579 }
00580
00581 void ArmToROSJointState::publish()
00582 {
00583 if (arm != NULL)
00584 {
00585 sensor_msgs::JointState js;
00586 js.header.stamp = getROSTime();
00587 std::vector<double> q = arm->getJointPosition();
00588 std::vector<std::string> names=arm->getJointName();
00589 for (size_t i = 0; i < q.size(); i++)
00590 {
00591 js.name.push_back(names[i]);
00592 js.position.push_back(q[i]);
00593 js.effort.push_back(0);
00594 }
00595
00596 pub_.publish(js);
00597 }
00598 }
00599
00600 ArmToROSJointState::~ArmToROSJointState()
00601 {
00602 }
00603
00604 VirtualCameraToROSImage::VirtualCameraToROSImage(VirtualCamera *camera, std::string topic, std::string info_topic,
00605 int rate, int depth) :
00606 ROSPublisherInterface(info_topic, rate), cam(camera), image_topic(topic)
00607 {
00608 it.reset(new image_transport::ImageTransport(nh_));
00609 this->depth = depth;
00610 this->bw = camera->bw;
00611 }
00612
00613 void VirtualCameraToROSImage::createPublisher(ros::NodeHandle &nh)
00614 {
00615 ROS_INFO("VirtualCameraToROSImage publisher on topic %s", topic.c_str());
00616 while (!it)
00617 {
00618 ROS_INFO("VirtualCameraToROSImage Waiting for transport to be initialized...");
00619 }
00620 img_pub_ = it->advertise(image_topic, 1);
00621 pub_ = nh.advertise < sensor_msgs::CameraInfo > (topic, 1);
00622 }
00623
00624 void VirtualCameraToROSImage::publish()
00625 {
00626
00627 osg::ref_ptr < osg::Image > osgimage;
00628 if (depth)
00629 {
00630 osgimage = cam->depthTexture;
00631 }
00632 else
00633 {
00634 osgimage = cam->renderTexture;
00635 }
00636 if (osgimage != NULL && osgimage->getTotalSizeInBytes() != 0)
00637 {
00638
00639 int w, h, d;
00640 w = osgimage->s();
00641 h = osgimage->t();
00642 d = osgimage->getTotalSizeInBytes();
00643
00644 if (d != 0)
00645 {
00646 sensor_msgs::Image img;
00647 sensor_msgs::CameraInfo img_info;
00648 img_info.header.stamp = img.header.stamp = getROSTime();
00649 img_info.header.frame_id = img.header.frame_id = cam->frameId;
00650 if (depth)
00651 img.encoding = std::string("32FC1");
00652 else if (bw)
00653 img.encoding = std::string("mono8");
00654 else
00655 img.encoding = std::string("rgb8");
00656
00657 img.is_bigendian = 0;
00658 img.height = h;
00659 img.width = w;
00660 if (bw)
00661 d /=3;
00662 img.step = d / h;
00663 img.data.resize(d);
00664 img_info.width = w;
00665 img_info.height = h;
00666
00667 img_info.D.resize(4, 0.0);
00668
00669 img_info.R[0] = 1.0;
00670 img_info.R[4] = 1.0;
00671 img_info.R[8] = 1.0;
00672
00673 img_info.K[0] = cam->fx;
00674 img_info.K[2] = cam->cx;
00675 img_info.K[4] = cam->fy;
00676 img_info.K[5] = cam->cy;
00677 img_info.K[8] = 1;
00678
00679 img_info.P[0] = cam->fx;
00680 img_info.P[2] = cam->cx;
00681 img_info.P[3] = cam->Tx;
00682 img_info.P[5] = cam->fy;
00683 img_info.P[6] = cam->cy;
00684 img_info.P[7] = cam->Ty;
00685 img_info.P[10] = 1;
00686
00687 img_info.roi.x_offset = 0;
00688 img_info.roi.y_offset = 0;
00689 img_info.roi.height = img_info.height;
00690 img_info.roi.width = img_info.width;
00691 img_info.roi.do_rectify = false;
00692
00693 img_info.binning_x = 0;
00694 img_info.binning_y = 0;
00695
00696 double fov, aspect, near, far;
00697 cam->textureCamera->getProjectionMatrixAsPerspective(fov, aspect, near, far);
00698 double a = far / (far - near);
00699 double b = (far * near) / (near - far);
00700
00701
00702
00703 unsigned char *virtualdata = (unsigned char*)osgimage->data();
00704
00705
00706
00707
00708 if (virtualdata != NULL)
00709 for (int i = 0; i < h; i++)
00710 {
00711 unsigned char *srcRow = virtualdata + i * img.step*(bw?3:1);
00712 unsigned char *dstRow = img.data.data() + (h - i - 1) * img.step;
00713 for (unsigned int j = 0;
00714 (!depth && j < img.step) || (depth && j < w); j++)
00715 {
00716 if (bw)
00717 {
00718 dstRow[j] = srcRow[j * 3] * 0.2989;
00719 dstRow[j] += srcRow[j * 3 + 1] * 0.5870;
00720 dstRow[j] += srcRow[j * 3 + 2] * 0.1140;
00721 }
00722 else if (depth)
00723 {
00724 float D = b / (((float*)srcRow)[j] - a);
00725 if (D == far)
00726 D = INFINITY;
00727 else if (D == near)
00728 D = -INFINITY;
00729 else if (!isfinite(D) || D < near || D > far)
00730 D = NAN;
00731 ((float*)dstRow)[j] = D;
00732 }
00733 else
00734 dstRow[j] = srcRow[j];
00735 }
00736 }
00737 else
00738 memset(&(img.data.front()), 0, d);
00739
00740 img_pub_.publish(img);
00741 pub_.publish(img_info);
00742 }
00743 }
00744
00745 }
00746
00747 VirtualCameraToROSImage::~VirtualCameraToROSImage()
00748 {
00749 }
00750
00751 RangeSensorToROSRange::RangeSensorToROSRange(VirtualRangeSensor *rangesensor, std::string topic, int rate) :
00752 ROSPublisherInterface(topic, rate), rs(rangesensor)
00753 {
00754 }
00755
00756 void RangeSensorToROSRange::createPublisher(ros::NodeHandle &nh)
00757 {
00758 ROS_INFO("RangeSensorToROSRange publisher on topic %s", topic.c_str());
00759 pub_ = nh.advertise < sensor_msgs::Range > (topic, 1);
00760 }
00761
00762 void RangeSensorToROSRange::publish()
00763 {
00764 if (rs != NULL)
00765 {
00766 sensor_msgs::Range r;
00767 r.header.stamp = getROSTime();
00768 r.radiation_type = sensor_msgs::Range::ULTRASOUND;
00769 r.field_of_view = 0;
00770 r.min_range = 0;
00771 r.max_range = rs->range;
00772 r.range = (rs->node_tracker != NULL) ? rs->node_tracker->distance_to_obstacle : r.max_range;
00773
00774 pub_.publish(r);
00775 }
00776 }
00777
00778 RangeSensorToROSRange::~RangeSensorToROSRange()
00779 {
00780 }
00781
00782 MultibeamSensorToROS::MultibeamSensorToROS(MultibeamSensor *multibeamSensor, std::string topic, int rate) :
00783 ROSPublisherInterface(topic, rate), MB(multibeamSensor)
00784 {
00785 }
00786
00787 void MultibeamSensorToROS::createPublisher(ros::NodeHandle &nh)
00788 {
00789 ROS_INFO(" MultibeamSensorToROS publisher on topic %s", topic.c_str());
00790 pub_ = nh.advertise < sensor_msgs::LaserScan > (topic, 1);
00791 }
00792
00793 void MultibeamSensorToROS::publish()
00794 {
00795 if (MB != NULL)
00796 {
00797 sensor_msgs::LaserScan ls;
00798 ls.header.stamp = getROSTime();
00799 ls.header.frame_id = MB->name;
00800
00801 double fov, aspect, near, far;
00802
00803 MB->textureCamera->getProjectionMatrixAsPerspective(fov, aspect, near, far);
00804 ls.range_min = near;
00805 ls.range_max = MB->range;
00806 ls.angle_min = MB->initAngle * M_PI / 180;
00807 ls.angle_max = MB->finalAngle * M_PI / 180;
00808 ls.angle_increment = MB->angleIncr * M_PI / 180;
00809 ls.ranges.resize(MB->numpixels);
00810 std::vector<double> tmp;
00811 tmp.resize(MB->numpixels);
00812
00813 float * data = (float *)MB->depthTexture->data();
00814 double a = far / (far - near);
00815 double b = (far * near) / (near - far);
00816
00817 for (int i = 0; i < MB->numpixels; i++)
00818 {
00819 double Z = (data[i]);
00820 tmp[i] = b / (Z - a);
00821 if (tmp[i] > MB->range)
00822 tmp[i] = MB->range;
00823 }
00824 for (int i = 0; i < MB->numpixels; i++)
00825 {
00826 ls.ranges[i] = (tmp[MB->remapVector[i].pixel1] * MB->remapVector[i].weight1
00827 + tmp[MB->remapVector[i].pixel2] * MB->remapVector[i].weight2) * MB->remapVector[i].distort;
00828 }
00829
00830
00831
00832
00833
00834
00835 pub_.publish(ls);
00836 }
00837 }
00838
00839 MultibeamSensorToROS::~MultibeamSensorToROS()
00840 {
00841 }
00842
00843 contactSensorToROS::contactSensorToROS(osg::Group *rootNode, BulletPhysics * physics, std::string target,
00844 std::string topic, int rate) :
00845 ROSPublisherInterface(topic, rate)
00846 {
00847 this->rootNode = rootNode;
00848 this->physics = physics;
00849 this->target = target;
00850 }
00851
00852 void contactSensorToROS::createPublisher(ros::NodeHandle &nh)
00853 {
00854 ROS_INFO("contactSensorToROS publisher on topic %s", topic.c_str());
00855 pub_ = nh.advertise < std_msgs::Bool > (topic, 1);
00856 }
00857
00858 void contactSensorToROS::publish()
00859 {
00860 int colliding = 0;
00861
00862 for (int i = 0; i < physics->getNumCollisions(); i++)
00863 {
00864 btPersistentManifold * col = physics->getCollision(i);
00865
00866
00867 btRigidBody* obA = static_cast<btRigidBody*>(col->getBody0());
00868 btRigidBody* obB = static_cast<btRigidBody*>(col->getBody1());
00869
00870
00871 CollisionDataType * data = (CollisionDataType *)obA->getUserPointer();
00872 CollisionDataType * data2 = (CollisionDataType *)obB->getUserPointer();
00873
00874 int numContacts = col->getNumContacts();
00875
00876 if (data2->getObjectName() == target || data->getObjectName() == target)
00877 {
00878 for (int j = 0; j < numContacts; j++)
00879 {
00880 btManifoldPoint pt = col->getContactPoint(j);
00881 if (pt.getDistance() < 0.f)
00882 colliding = 1;
00883 }
00884 }
00885
00886 }
00887 std_msgs::Bool msg;
00888 msg.data = colliding;
00889 pub_.publish(msg);
00890 }
00891
00892 contactSensorToROS::~contactSensorToROS()
00893 {
00894 }
00895
00896
00897 WorldToROSTF::WorldToROSTF(osg::Group *rootNode, std::vector< boost::shared_ptr<SimulatedIAUV> > iauvFile, std::vector<osg::ref_ptr<osg::Node> > objects, std::string worldRootName, unsigned int enableObjects, int rate ) :
00898 ROSPublisherInterface(worldRootName, rate)
00899 {
00900 iauvFile_ = iauvFile;
00901 objects_ = objects;
00902 rootNode_ = rootNode;
00903 for(int i = 0; i < iauvFile_.size(); i++)
00904 {
00905 KDL::Tree tree;
00906 if (!kdl_parser::treeFromFile(iauvFile[i].get()->urdf->URDFFile, tree))
00907 {
00908 ROS_ERROR("Failed to construct kdl tree");
00909 }
00910 else
00911 {
00912 ROS_INFO("Loaded tree, %d segments, %d joints", tree.getNrOfSegments(), tree.getNrOfJoints());
00913 }
00914
00915 osg::ref_ptr<osg::MatrixTransform> transform;
00916 nh_.setParam("tf_prefix", iauvFile_[i].get()->name);
00917 robot_pubs_.push_back(boost::shared_ptr<robot_state_publisher::RobotStatePublisher>(
00918 new robot_state_publisher::RobotStatePublisher(tree)));
00919
00920 findNodeVisitor findNode(iauvFile[i].get()->name);
00921 rootNode->accept(findNode);
00922 osg::Node *first = findNode.getFirst();
00923 if (first == NULL)
00924 {
00925 transform = NULL;
00926 }
00927 else
00928 {
00929 transform = dynamic_cast<osg::MatrixTransform*>(first);
00930 }
00931 transforms_.push_back(transform);
00932 }
00933 worldRootName_ = worldRootName;
00934 enableObjects_ = enableObjects;
00935 }
00936
00937 void WorldToROSTF::createPublisher(ros::NodeHandle &nh)
00938 {
00939 tfpub_ = boost::shared_ptr<tf::TransformBroadcaster>(new tf::TransformBroadcaster());
00940 }
00941
00942 void WorldToROSTF::publish()
00943 {
00944
00945
00946 for( int i = 0; i < iauvFile_.size(); i++ )
00947 {
00948 nh_.setParam("tf_prefix", iauvFile_[i].get()->name);
00949
00950 robot_pubs_[i]->publishTransforms(iauvFile_[i].get()->urdf->getFullJointMap(), getROSTime());
00951
00952 robot_pubs_[i]->publishFixedTransforms();
00953
00954 if (transforms_[i] != NULL)
00955 {
00956 osg::Matrixd mat = transforms_[i]->getMatrix();
00957 osg::Vec3d pos = mat.getTrans();
00958 osg::Quat rot = mat.getRotate();
00959
00960 tf::Vector3 p(pos.x(), pos.y(), pos.z());
00961 tf::Quaternion q(rot.x(), rot.y(), rot.z(), rot.w());
00962 tf::Pose pose(q,p);
00963 tf::StampedTransform t(pose, getROSTime(), "/" + worldRootName_, "/"+iauvFile_[i].get()->name);
00964
00965 tf::Vector3 p2(0, 0, 0);
00966 tf::Quaternion q2(0, 0, 0, 1);
00967 tf::Pose pose2(q2,p2);
00968 tf::StampedTransform t2(pose2, getROSTime(), "/"+iauvFile_[i].get()->name, "/"+iauvFile_[i].get()->name + "/base_link");
00969
00970 tfpub_->sendTransform(t2);
00971 tfpub_->sendTransform(t);
00972 }
00973 }
00974
00975
00976 if(enableObjects_)
00977 {
00978
00979 boost::shared_ptr<osg::Matrix> LWMat=getWorldCoords(findRN("localizedWorld",rootNode_));
00980 LWMat->invert(*LWMat);
00981
00982 for(unsigned int i=0;i<objects_.size();i++)
00983 {
00984 boost::shared_ptr<osg::Matrix> objectMat= getWorldCoords(objects_[i]);
00985
00986 osg::Matrixd res=*objectMat * *LWMat;
00987
00988 tf::Vector3 p2(res.getTrans().x(), res.getTrans().y(), res.getTrans().z());
00989 tf::Quaternion q2(res.getRotate().x(), res.getRotate().y(), res.getRotate().z(), res.getRotate().w());
00990 tf::Pose pose2(q2,p2);
00991 tf::StampedTransform t(pose2, getROSTime(), "/" + worldRootName_, objects_[i]->getName());
00992
00993 tfpub_->sendTransform(t);
00994 }
00995
00996 }
00997
00998
00999
01000 }
01001
01002 WorldToROSTF::~WorldToROSTF()
01003 {
01004 }