sick_ldmrs_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2015, DFKI GmbH
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of DFKI GmbH nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *  Created on: 20.11.2015
00030  *
00031  *      Authors:
00032  *         Martin Günther <martin.guenther@dfki.de>
00033  *         Jochen Sprickerhof <jochen@sprickerhof.de>
00034  *
00035  */
00036 
00037 #include <iostream>
00038 
00039 #include <pcl_conversions/pcl_conversions.h>
00040 
00041 #include "sick_ldmrs_driver/sick_ldmrs_node.hpp"
00042 
00043 #include <sick_ldmrs/datatypes/EvalCaseResults.hpp>
00044 #include <sick_ldmrs/datatypes/EvalCases.hpp>
00045 #include <sick_ldmrs/datatypes/Fields.hpp>
00046 #include <sick_ldmrs/datatypes/Measurement.hpp>
00047 #include <sick_ldmrs/datatypes/Msg.hpp>
00048 #include <sick_ldmrs/datatypes/Scan.hpp>
00049 
00050 #include <sick_ldmrs/devices/LD_MRS.hpp>
00051 
00052 #include <sick_ldmrs/tools/errorhandler.hpp>
00053 #include <sick_ldmrs/tools/toolbox.hpp>
00054 
00055 #include <sick_ldmrs_msgs/ObjectArray.h>
00056 #include <tf/transform_datatypes.h>
00057 
00058 
00059 namespace sick_ldmrs_driver
00060 {
00061 
00062 SickLDMRS::SickLDMRS(Manager *manager, boost::shared_ptr<diagnostic_updater::Updater> diagnostics)
00063   : application::BasicApplication()
00064   , diagnostics_(diagnostics)
00065   , manager_(manager)
00066   , expected_frequency_(12.5)
00067   , initialized_(false)
00068 {
00069   dynamic_reconfigure::Server<SickLDMRSDriverConfig>::CallbackType f;
00070   f = boost::bind(&SickLDMRS::update_config, this, _1, _2);
00071   dynamic_reconfigure_server_.setCallback(f);
00072 
00073   // point cloud publisher
00074   pub_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud", 100);
00075 
00076   object_pub_ = nh_.advertise<sick_ldmrs_msgs::ObjectArray>("objects", 1);
00077 
00078   diagnostics_->setHardwareID("none");   // set from device after connection
00079   diagnostics_->add("device info", this, &SickLDMRS::produce_diagnostics);
00080   diagnosticPub_ = new diagnostic_updater::DiagnosedPublisher<sensor_msgs::PointCloud2>(pub_, *diagnostics_,
00081       // frequency should be target +- 10%
00082       diagnostic_updater::FrequencyStatusParam(&expected_frequency_, &expected_frequency_, 0.1, 10),
00083       // timestamp delta can be from -1 seconds to 1.3x what it ideally is at the lowest frequency
00084       diagnostic_updater::TimeStampStatusParam(-1, 1.3 * 1.0 / 12.5));
00085 }
00086 
00087 SickLDMRS::~SickLDMRS()
00088 {
00089   delete diagnosticPub_;
00090 }
00091 
00092 void SickLDMRS::init()
00093 {
00094   if (isUpsideDown())
00095   {
00096     ROS_ERROR("Error: upside down mode is active, please disable!");
00097   }
00098   initialized_ = true;
00099   update_config(config_);
00100 }
00101 
00102 void SickLDMRS::produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
00103 {
00104   devices::LDMRS* ldmrs;
00105   ldmrs = dynamic_cast<devices::LDMRS*>(manager_->getFirstDeviceByType(Sourcetype_LDMRS));
00106   stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Device information.");
00107 
00108   // REP-138 values (http://www.ros.org/reps/rep-0138.html#diagnostic-keys)
00109   stat.add("IP Address", ldmrs->getIpAddress());
00110   stat.add("IP Port", 12002);   // LUX port number
00111   stat.add("Vendor Name", "SICK");
00112   stat.add("Product Name", "LD-MRS");
00113   stat.add("Firmware Version", ldmrs->getFirmwareVersion());  // includes date, e.g. "3.03.5 2015-01-14 13:32"
00114   stat.add("Device ID", ldmrs->getSerialNumber());
00115 }
00116 
00117 void SickLDMRS::setData(BasicData &data)
00118 {
00119   std::string datatypeStr;
00120   std::string sourceIdStr;
00121 
00122   switch (data.getDatatype())
00123   {
00124   case Datatype_Scan:
00125     datatypeStr = "Scan (" + ::toString(((Scan&)data).getNumPoints()) + " points)";
00126     {
00127       Scan* scan = dynamic_cast<Scan*>(&data);
00128       std::vector<ScannerInfo> scannerInfos = scan->getScannerInfos();
00129       if (scannerInfos.size() != 1)
00130       {
00131         ROS_ERROR("Expected exactly 1 scannerInfo, got %zu!", scannerInfos.size());
00132         return;
00133       }
00134 
00135       const Time& time = scannerInfos[0].getStartTimestamp();
00136       ROS_DEBUG("setData(): Scan start time: %s (%s)",
00137                 time.toString().c_str(),
00138                 time.toLongString().c_str());
00139 
00140       PointCloud::Ptr cloud = boost::make_shared<PointCloud>();
00141       cloud->header.frame_id = config_.frame_id;
00142       // not using time stamp from scanner here, because it is delayed by up to 1.5 seconds
00143       cloud->header.stamp = (ros::Time::now().toSec() - 1 / expected_frequency_) * 1e6;
00144 
00145       cloud->height = 1;
00146       cloud->width = scan->size();
00147       for (size_t i = 0; i < scan->size(); ++i)
00148       {
00149         const ScanPoint& p = (*scan)[i];
00150         sick_ldmrs_msgs::SICK_LDMRS_Point np;
00151         np.x = p.getX();
00152         np.y = p.getY();
00153         np.z = p.getZ();
00154         np.echowidth = p.getEchoWidth();
00155         np.layer = p.getLayer() + (scannerInfos[0].isRearMirrorSide() ? 4 : 0);
00156         np.echo = p.getEchoNum();
00157         np.flags = p.getFlags();
00158         cloud->points.push_back(np);
00159       }
00160 
00161       sensor_msgs::PointCloud2 msg;
00162       pcl::toROSMsg(*cloud, msg);
00163       diagnosticPub_->publish(msg);
00164     }
00165     break;
00166   case Datatype_Objects:
00167     datatypeStr = "Objects (" + ::toString(((ObjectList&)data).size()) + " objects)";
00168     pubObjects((ObjectList&)data);
00169     break;
00170   case Datatype_Fields:
00171     datatypeStr = "Fields (" + ::toString(((Fields&)data).getFields().size()) + " fields, " +
00172                   ::toString(((Fields&)data).getNumberOfValidFields()) + " of which are valid)";
00173     break;
00174   case Datatype_EvalCases:
00175     datatypeStr = "EvalCases (" + ::toString(((EvalCases&)data).getEvalCases().size()) + " cases)";
00176     break;
00177   case Datatype_EvalCaseResults:
00178     datatypeStr = "EvalCaseResults (" + ::toString(((EvalCaseResults&)data).size()) + " case results)";
00179     break;
00180   case Datatype_Msg:
00181     datatypeStr = "Msg (" + ((Msg&)data).toString() + ")";
00182     diagnostics_->broadcast(diagnostic_msgs::DiagnosticStatus::WARN, ((Msg&)data).toString());
00183     diagnostics_->force_update();
00184     break;
00185   case Datatype_MeasurementList:
00186     datatypeStr = "MeasurementList (" + ::toString(((MeasurementList&)data).m_list.size()) + " entries)";
00187     break;
00188   default:
00189     datatypeStr = "(unknown)";
00190   }
00191 
00192   sourceIdStr = ::toString(data.getSourceId());
00193 
00194   ROS_DEBUG("setData(): Called with data of type %s from ID %s", datatypeStr.c_str(), sourceIdStr.c_str());
00195 }
00196 
00197 void SickLDMRS::validate_config(SickLDMRSDriverConfig &conf)
00198 {
00199   if (conf.start_angle <= conf.end_angle)
00200   {
00201     ROS_WARN("Start angle must be greater than end angle. Adjusting start_angle.");
00202     conf.start_angle = conf.end_angle;  // TODO: - 2 * ticks2rad
00203   }
00204 
00205   if (conf.angular_resolution_type != SickLDMRSDriver_ConstantRes
00206       && conf.scan_frequency != SickLDMRSDriver_ScanFreq1250)
00207   {
00208     ROS_WARN("Focused/flexible resolution only available at 12.5 Hz scan frequency. Adjusting scan frequency.");
00209     conf.scan_frequency = SickLDMRSDriver_ScanFreq1250;
00210   }
00211 
00212   if (conf.ignore_near_range && conf.layer_range_reduction != SickLDMRSDriver_RangeLowerReduced)
00213   {
00214     ROS_WARN("If ignore_near_range is set, layer_range_reduction must be set to 'Lower 4 layers reduced range'. Adjusting layer_range_reduction.");
00215     conf.layer_range_reduction = SickLDMRSDriver_RangeLowerReduced;
00216   }
00217 
00218   validate_flexres_resolution(conf.flexres_resolution1);
00219   validate_flexres_resolution(conf.flexres_resolution2);
00220   validate_flexres_resolution(conf.flexres_resolution3);
00221   validate_flexres_resolution(conf.flexres_resolution4);
00222   validate_flexres_resolution(conf.flexres_resolution5);
00223   validate_flexres_resolution(conf.flexres_resolution6);
00224   validate_flexres_resolution(conf.flexres_resolution7);
00225   validate_flexres_resolution(conf.flexres_resolution8);
00226   validate_flexres_start_angle(conf.flexres_start_angle1, conf.flexres_start_angle2);
00227   validate_flexres_start_angle(conf.flexres_start_angle2, conf.flexres_start_angle3);
00228   validate_flexres_start_angle(conf.flexres_start_angle3, conf.flexres_start_angle4);
00229   validate_flexres_start_angle(conf.flexres_start_angle4, conf.flexres_start_angle5);
00230   validate_flexres_start_angle(conf.flexres_start_angle5, conf.flexres_start_angle6);
00231   validate_flexres_start_angle(conf.flexres_start_angle6, conf.flexres_start_angle7);
00232   validate_flexres_start_angle(conf.flexres_start_angle7, conf.flexres_start_angle8);
00233 }
00234 
00235 void SickLDMRS::validate_flexres_resolution(int &res)
00236 {
00237   // Check that res is one of 4/8/16/32. This has to be checked manually here, since
00238   // the dynamic parameter is an int with min 4 and max 32, so dynamic reconfigure
00239   // doesn't prevent the user from setting an invalid value inside that range.
00240   // (Values outside that range will still be clamped automatically.)
00241 
00242   switch (res)
00243   {
00244   case SickLDMRSDriver_Res0125:
00245   case SickLDMRSDriver_Res0250:
00246   case SickLDMRSDriver_Res0500:
00247   case SickLDMRSDriver_Res1000:
00248     break;
00249   default:
00250     ROS_WARN("Invalid flexres resolution %d! Setting to 32 (= 1 degree).", res);
00251     res = SickLDMRSDriver_Res1000;
00252     break;
00253   }
00254 }
00255 
00256 void SickLDMRS::validate_flexres_start_angle(double &angle1, double &angle2)
00257 {
00258   // make sure the angles are monotonically decreasing
00259   if (angle2 > angle1)
00260   {
00261     angle2 = angle1;
00262   }
00263 }
00264 
00265 void SickLDMRS::pubObjects(datatypes::ObjectList &objects)
00266 {
00267   sick_ldmrs_msgs::ObjectArray oa;
00268   oa.header.frame_id = config_.frame_id;
00269   // not using time stamp from scanner here, because it is delayed by up to 1.5 seconds
00270   oa.header.stamp = ros::Time::now();
00271   oa.objects.resize(objects.size());
00272 
00273   for (int i = 0; i < objects.size(); i++)
00274   {
00275     oa.objects[i].id = objects[i].getObjectId();
00276     oa.objects[i].tracking_time = ros::Time::now() - ros::Duration(objects[i].getObjectAge() / expected_frequency_);
00277     oa.objects[i].last_seen = ros::Time::now() - ros::Duration(objects[i].getHiddenStatusAge() / expected_frequency_);
00278     oa.objects[i].velocity.twist.linear.x = objects[i].getAbsoluteVelocity().getX();
00279     oa.objects[i].velocity.twist.linear.y = objects[i].getAbsoluteVelocity().getY();
00280     oa.objects[i].velocity.twist.linear.x = objects[i].getAbsoluteVelocity().getX();
00281     oa.objects[i].velocity.twist.linear.y = objects[i].getAbsoluteVelocity().getY();
00282     oa.objects[i].velocity.covariance[0] = objects[i].getAbsoluteVelocitySigma().getX();
00283     oa.objects[i].velocity.covariance[7] = objects[i].getAbsoluteVelocitySigma().getX();
00284 
00285     oa.objects[i].bounding_box_center.position.x = objects[i].getBoundingBoxCenter().getX();
00286     oa.objects[i].bounding_box_center.position.y = objects[i].getBoundingBoxCenter().getY();
00287     oa.objects[i].bounding_box_size.x = objects[i].getBoundingBox().getX();
00288     oa.objects[i].bounding_box_size.y = objects[i].getBoundingBox().getY();
00289 
00290     oa.objects[i].object_box_center.pose.position.x = objects[i].getCenterPoint().getX();
00291     oa.objects[i].object_box_center.pose.position.y = objects[i].getCenterPoint().getY();
00292     oa.objects[i].object_box_center.pose.orientation = tf::createQuaternionMsgFromYaw(objects[i].getCourseAngle());
00293     oa.objects[i].object_box_center.covariance[0] = objects[i].getCenterPointSigma().getX();
00294     oa.objects[i].object_box_center.covariance[7] = objects[i].getCenterPointSigma().getY();
00295     oa.objects[i].object_box_center.covariance[35] = objects[i].getCourseAngleSigma();
00296     oa.objects[i].object_box_size.x = objects[i].getObjectBox().getX();
00297     oa.objects[i].object_box_size.y = objects[i].getObjectBox().getY();
00298 
00299     datatypes::Polygon2D contour = objects[i].getContourPoints();
00300     oa.objects[i].contour_points.resize(contour.size());
00301     for (int j = 0; j < contour.size(); j++)
00302     {
00303       oa.objects[i].contour_points[j].x = contour[j].getX();
00304       oa.objects[i].contour_points[j].y = contour[j].getY();
00305     }
00306 
00307     //std::cout << objects[i].toString() << std::endl;
00308   }
00309 
00310   object_pub_.publish(oa);
00311 }
00312 
00313 bool SickLDMRS::isUpsideDown()
00314 {
00315   devices::LDMRS* ldmrs;
00316   ldmrs = dynamic_cast<devices::LDMRS*>(manager_->getFirstDeviceByType(Sourcetype_LDMRS));
00317   if (ldmrs == NULL)
00318   {
00319     ROS_WARN("isUpsideDown: no connection to LDMRS!");
00320     return true;
00321   }
00322 
00323   UINT32 code;
00324   ldmrs->getParameter(devices::ParaUpsideDownMode, &code);
00325   return (code != 0);
00326 }
00327 
00328 void SickLDMRS::printFlexResError()
00329 {
00330   devices::LDMRS* ldmrs;
00331   ldmrs = dynamic_cast<devices::LDMRS*>(manager_->getFirstDeviceByType(Sourcetype_LDMRS));
00332   if (ldmrs == NULL)
00333   {
00334     ROS_WARN("printFlexResError: no connection to LDMRS!");
00335     return;
00336   }
00337 
00338   UINT32 code;
00339   ldmrs->getParameter(devices::ParaDetailedError, &code);
00340   std::string msg = flexres_err_to_string(code);
00341   ROS_ERROR("FlexRes detailed error: %s", msg.c_str());
00342 }
00343 
00344 void SickLDMRS::update_config(SickLDMRSDriverConfig &new_config, uint32_t level)
00345 {
00346   validate_config(new_config);
00347   config_ = new_config;
00348 
00349   if (!initialized_)
00350     return;
00351 
00352   ROS_INFO("Updating config...");
00353 
00354   devices::LDMRS* ldmrs;
00355   ldmrs = dynamic_cast<devices::LDMRS*>(manager_->getFirstDeviceByType(Sourcetype_LDMRS));
00356   if (ldmrs == NULL)
00357   {
00358     ROS_WARN("update_config: no connection to LDMRS!");
00359     return;
00360   }
00361 
00362   // TODO: if (new_config.start_angle < config_.end_angle): first update end angle,
00363   // then start angle to ensure that always start_angle > end_angle; see comments
00364   // in LuxBase::cmd_setScanAngles().
00365   if (!ldmrs->setScanAngles(new_config.start_angle, new_config.end_angle))
00366     ROS_WARN("Sending param not successful: ");
00367 
00368   switch (config_.scan_frequency)
00369   {
00370   case SickLDMRSDriver_ScanFreq1250:
00371     expected_frequency_ = 12.5d;
00372     break;
00373   case SickLDMRSDriver_ScanFreq2500:
00374     expected_frequency_ = 25.0d;
00375     break;
00376   case SickLDMRSDriver_ScanFreq5000:
00377     expected_frequency_ = 50.0d;
00378     break;
00379   default:
00380     ROS_ERROR("Unknown scan frequency: %i", config_.scan_frequency);
00381     break;
00382   }
00383 
00384   if (!ldmrs->setScanFrequency(expected_frequency_))
00385     ROS_WARN("Sending param not successful: ScanFrequency");
00386   if (!ldmrs->setSyncAngleOffset(config_.sync_angle_offset))
00387     ROS_WARN("Sending param not successful: SyncAngleOffset");
00388   if (!ldmrs->setParameter(devices::ParaContourPointDensity, config_.contour_point_density))
00389     ROS_WARN("Sending param not successful: ContourPointDensity");
00390   if (!ldmrs->setParameter(devices::ParaMinimumObjectAge, config_.min_object_age))
00391     ROS_WARN("Sending param not successful: MinimumObjectAge");
00392   if (!ldmrs->setParameter(devices::ParaMaximumPredictionAge, config_.max_prediction_age))
00393     ROS_WARN("Sending param not successful: MaximumPredictionAge");
00394   if (!ldmrs->setParameter(devices::ParaRangeReduction, config_.layer_range_reduction))
00395     ROS_WARN("Sending param not successful: RangeReduction");
00396   if (!ldmrs->setParameter(devices::ParaIgnoreNearRange, config_.ignore_near_range ? 1 : 0))
00397     ROS_WARN("Sending param not successful: IgnoreNearRange");
00398   if (!ldmrs->setParameter(devices::ParaSensitivityControl, config_.sensitivity_control ? 1 : 0))
00399     ROS_WARN("Sending param not successful: SensitivityControl");
00400 
00401   if (config_.angular_resolution_type == SickLDMRSDriver_FlexRes)
00402   {
00403     std::vector<std::pair<int, int> > res_map, res_map_filtered;
00404     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle1 * rad2deg * 32.0), config_.flexres_resolution1));
00405     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle2 * rad2deg * 32.0), config_.flexres_resolution2));
00406     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle3 * rad2deg * 32.0), config_.flexres_resolution3));
00407     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle4 * rad2deg * 32.0), config_.flexres_resolution4));
00408     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle5 * rad2deg * 32.0), config_.flexres_resolution5));
00409     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle6 * rad2deg * 32.0), config_.flexres_resolution6));
00410     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle7 * rad2deg * 32.0), config_.flexres_resolution7));
00411     res_map.push_back(std::pair<int, int>(round(config_.flexres_start_angle8 * rad2deg * 32.0), config_.flexres_resolution8));
00412 
00413     // --- skip zero-length sectors
00414     for (int i = 0; i < res_map.size() - 1; ++i)
00415     {
00416       if (res_map[i].first > res_map[i + 1].first)
00417       {
00418         res_map_filtered.push_back(res_map[i]);
00419       }
00420     }
00421     if (res_map[7].first > (-1918))   // -1918 = minimum start angle
00422     {
00423       res_map_filtered.push_back(res_map[7]);
00424     }
00425 
00426     // --- ensure constraints are met
00427     int shots_per_scan = 0;
00428     double sum_res0125 = 0;
00429     for (int i = 0; i < res_map_filtered.size() - 1; ++i)
00430     {
00431       // sector angle in degrees
00432       double sector_angle = (res_map_filtered[i].first - res_map_filtered[i + 1].first) / 32.0;
00433 
00434       shots_per_scan += sector_angle * 32.0 / res_map_filtered[i].second;
00435       if (res_map_filtered[i].second == SickLDMRSDriver_Res0125)
00436       {
00437         sum_res0125 += sector_angle;
00438       }
00439     }
00440 
00441     if (shots_per_scan > 440)
00442     {
00443       ROS_WARN("FlexRes: The number of shots per scan must be at most 440. Not updating FlexRes config!");
00444       return;
00445     }
00446     if (sum_res0125 > 20.0)
00447     {
00448       ROS_WARN("FlexRes: The sectors with a resolution of 0.125 deg must not sum up to more than 20 deg. Not updating FlexRes config!");
00449       return;
00450     }
00451 
00452     // --- switch to constant resolution
00453     // when applying FlexRes params, the angular resolution type has to be set
00454     // to something other than FlexRes
00455     if (!ldmrs->setParameter(devices::ParaAngularResolutionType, SickLDMRSDriver_ConstantRes))
00456       ROS_WARN("Sending param not successful: AngularResolutionType");
00457 
00458     // sleep 10 seconds so that new config is applied by the scanner
00459     usleep(10e6);
00460 
00461     // --- send FlexRes params to scanner
00462     if (!ldmrs->setParameter(devices::ParaNumSectors, res_map_filtered.size()))
00463       printFlexResError();
00464 
00465     for (int i = 0; i < res_map_filtered.size(); ++i)
00466     {
00467       // set sector start angle
00468       if (!ldmrs->setParameter((devices::MrsParameterId)(0x4001 + i), res_map_filtered[i].first))
00469         printFlexResError();
00470 
00471       // set sector resolution
00472       if (!ldmrs->setParameter((devices::MrsParameterId)(0x4009 + i), res_map_filtered[i].second))
00473         printFlexResError();
00474     }
00475   }
00476 
00477   // set angular resolution type *after* FlexRes config!
00478   if (!ldmrs->setParameter(devices::ParaAngularResolutionType, config_.angular_resolution_type))
00479     ROS_WARN("Sending param not successful: AngularResolutionType");
00480 
00481   ROS_INFO("... done updating config.");
00482 }
00483 
00484 std::string SickLDMRS::flexres_err_to_string(const UINT32 code) const
00485 {
00486   switch (code)
00487   {
00488   case devices::ErrFlexResNumShotsInvalid:
00489     return "The number of shots per scan is higher than 440.";
00490   case devices::ErrFlexResSizeOneEighthSectorInvalid:
00491     return "The sectors with a resolution of 0.125 deg sum up to more than 20 deg.";
00492   case devices::ErrFlexResFreqInvalid:
00493     return "The scan frequency is not 12.5Hz.";
00494   case devices::ErrFlexResSectorsOverlapping:
00495     return "The start angles of the sectors decrease not strictly monotone.";
00496   case devices::ErrFlexResScannerNotIdle:
00497     return "Could not set FlexRes parameter because the sensor is in flex res mode and not idle.";
00498   case devices::ErrFlexResResolutionInvalid:
00499     return "The resolution of one sector is not 4, 8, 16 or 32 (0.125 deg, 0.25 deg, 0.5 deg, 1 deg).";
00500   case devices::ErrFlexResNumSectorsInvalid:
00501     return "The number of sectors is larger than 8.";
00502   default:
00503     std::ostringstream ss;
00504     ss << "UNKNOWN ERROR CODE (" << code << ")";
00505     return ss.str();
00506   }
00507 }
00508 
00509 } /* namespace sick_ldmrs_driver */
00510 
00511 
00512 int main(int argc, char **argv)
00513 {
00514   ros::init(argc, argv, "sick_ldmrs_node");
00515   boost::shared_ptr<diagnostic_updater::Updater> diagnostics
00516     = boost::make_shared<diagnostic_updater::Updater>();
00517 
00518   // The MRS-App connects to an MRS, reads its configuration and receives all incoming data.
00519   // First, create the manager object. The manager handles devices, collects
00520   // device data and forwards it to the application(s).
00521   ROS_INFO("Creating the manager.");
00522   Manager manager;
00523 
00524   // Add the application. As the devices may send configuration data only once
00525   // at startup, the applications must be present before the devices are
00526   // started.
00527   Sourcetype type;
00528   std::string name;
00529   UINT16 id;
00530   bool result = false;
00531 
00532   ROS_INFO("Adding the application SickLDMRS.");
00533   name = "Sick LDMRS ROS Driver App";
00534   id = 1356;
00535 
00536   sick_ldmrs_driver::SickLDMRS app(&manager, diagnostics);
00537   app.setApplicationName(name);
00538 
00539   result = manager.addApplication(&app, id);
00540   if (result == false)
00541   {
00542     ROS_ERROR("Failed to add application %s, aborting!", name.c_str());
00543     return EXIT_FAILURE;
00544   }
00545   ROS_INFO("Application is running.");
00546 
00547   //
00548   // Add and run the sensor
00549   //
00550   // The MRS device could be configured like this:
00551   // m_weWantScanData:          true
00552   // m_weWantObjectData:        true
00553   // m_weWantFieldData:         false
00554   // m_weWantScanDataFromSopas: false
00555   ROS_INFO("Adding the LDMRS device.");
00556   devices::LDMRS* ldmrs = new devices::LDMRS(&manager);
00557   ldmrs->setWeWantObjectData(true);
00558   std::string hostname;
00559   ros::NodeHandle nh("~");
00560   nh.param<std::string>("hostname", hostname, "192.168.0.1");
00561   ROS_INFO("Set IP address to %s", hostname.c_str());
00562   ldmrs->setIpAddress(hostname);
00563   name = "LDMRS-1";
00564   id = 1;
00565   result = manager.addAndRunDevice(ldmrs, name, id);
00566   if (result == false)
00567   {
00568     ROS_ERROR("Failed to add device %s, aborting!", name.c_str());
00569     return EXIT_FAILURE;
00570   }
00571 
00572   std::string serial_number = ldmrs->getSerialNumber();
00573   diagnostics->setHardwareID(serial_number);
00574 
00575   ROS_INFO("LD-MRS Firmware version is %s", ldmrs->getFirmwareVersion().c_str());
00576 
00577   // we need to initialize the app after setting up the ldmrs device
00578   app.init();
00579 
00580   ROS_INFO("%s is initialized.", ros::this_node::getName().c_str());
00581 
00582   ros::Rate r(10.0);
00583   while (ros::ok())
00584   {
00585     ros::spinOnce();
00586     diagnostics->update();
00587     r.sleep();
00588   }
00589 
00590   return EXIT_SUCCESS;
00591 }


sick_ldmrs_driver
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Thu May 9 2019 02:25:11