43 #include <sick_ldmrs/datatypes/EvalCaseResults.hpp> 44 #include <sick_ldmrs/datatypes/EvalCases.hpp> 45 #include <sick_ldmrs/datatypes/Fields.hpp> 46 #include <sick_ldmrs/datatypes/Measurement.hpp> 47 #include <sick_ldmrs/datatypes/Msg.hpp> 48 #include <sick_ldmrs/datatypes/Scan.hpp> 50 #include <sick_ldmrs/devices/LD_MRS.hpp> 52 #include <sick_ldmrs/tools/errorhandler.hpp> 53 #include <sick_ldmrs/tools/toolbox.hpp> 55 #include <sick_ldmrs_msgs/ObjectArray.h> 63 : application::BasicApplication()
64 , diagnostics_(diagnostics)
66 , expected_frequency_(12.5)
69 dynamic_reconfigure::Server<SickLDMRSDriverConfig>::CallbackType
f;
96 ROS_ERROR(
"Error: upside down mode is active, please disable!");
104 devices::LDMRS* ldmrs;
105 ldmrs =
dynamic_cast<devices::LDMRS*
>(
manager_->getFirstDeviceByType(Sourcetype_LDMRS));
106 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Device information.");
109 stat.
add(
"IP Address", ldmrs->getIpAddress());
110 stat.
add(
"IP Port", 12002);
111 stat.
add(
"Vendor Name",
"SICK");
112 stat.
add(
"Product Name",
"LD-MRS");
113 stat.
add(
"Firmware Version", ldmrs->getFirmwareVersion());
114 stat.
add(
"Device ID", ldmrs->getSerialNumber());
119 std::string datatypeStr;
120 std::string sourceIdStr;
122 switch (data.getDatatype())
125 datatypeStr =
"Scan (" + ::toString(((Scan&)data).getNumPoints()) +
" points)";
127 Scan* scan =
dynamic_cast<Scan*
>(&data);
128 std::vector<ScannerInfo> scannerInfos = scan->getScannerInfos();
129 if (scannerInfos.size() != 1)
131 ROS_ERROR(
"Expected exactly 1 scannerInfo, got %zu!", scannerInfos.size());
135 const Time& time = scannerInfos[0].getStartTimestamp();
136 ROS_DEBUG(
"setData(): Scan start time: %s (%s)",
137 time.toString().c_str(),
138 time.toLongString().c_str());
140 PointCloud::Ptr cloud = boost::make_shared<PointCloud>();
141 cloud->header.frame_id =
config_.frame_id;
146 cloud->width = scan->size();
147 for (
size_t i = 0; i < scan->size(); ++i)
149 const ScanPoint& p = (*scan)[i];
155 np.
layer = p.getLayer() + (scannerInfos[0].isRearMirrorSide() ? 4 : 0);
156 np.
echo = p.getEchoNum();
157 np.
flags = p.getFlags();
158 cloud->points.push_back(np);
161 sensor_msgs::PointCloud2
msg;
166 case Datatype_Objects:
167 datatypeStr =
"Objects (" + ::toString(((ObjectList&)data).size()) +
" objects)";
170 case Datatype_Fields:
171 datatypeStr =
"Fields (" + ::toString(((Fields&)data).getFields().size()) +
" fields, " +
172 ::toString(((Fields&)data).getNumberOfValidFields()) +
" of which are valid)";
174 case Datatype_EvalCases:
175 datatypeStr =
"EvalCases (" + ::toString(((EvalCases&)data).getEvalCases().size()) +
" cases)";
177 case Datatype_EvalCaseResults:
178 datatypeStr =
"EvalCaseResults (" + ::toString(((EvalCaseResults&)data).size()) +
" case results)";
181 datatypeStr =
"Msg (" + ((
Msg&)data).toString() +
")";
182 diagnostics_->broadcast(diagnostic_msgs::DiagnosticStatus::WARN, ((
Msg&)data).toString());
185 case Datatype_MeasurementList:
186 datatypeStr =
"MeasurementList (" + ::toString(((MeasurementList&)data).m_list.size()) +
" entries)";
189 datatypeStr =
"(unknown)";
192 sourceIdStr = ::toString(data.getSourceId());
194 ROS_DEBUG(
"setData(): Called with data of type %s from ID %s", datatypeStr.c_str(), sourceIdStr.c_str());
199 if (conf.start_angle <= conf.end_angle)
201 ROS_WARN(
"Start angle must be greater than end angle. Adjusting start_angle.");
202 conf.start_angle = conf.end_angle;
205 if (conf.angular_resolution_type != SickLDMRSDriver_ConstantRes
206 && conf.scan_frequency != SickLDMRSDriver_ScanFreq1250)
208 ROS_WARN(
"Focused/flexible resolution only available at 12.5 Hz scan frequency. Adjusting scan frequency.");
209 conf.scan_frequency = SickLDMRSDriver_ScanFreq1250;
212 if (conf.ignore_near_range && conf.layer_range_reduction != SickLDMRSDriver_RangeLowerReduced)
214 ROS_WARN(
"If ignore_near_range is set, layer_range_reduction must be set to 'Lower 4 layers reduced range'. Adjusting layer_range_reduction.");
215 conf.layer_range_reduction = SickLDMRSDriver_RangeLowerReduced;
244 case SickLDMRSDriver_Res0125:
245 case SickLDMRSDriver_Res0250:
246 case SickLDMRSDriver_Res0500:
247 case SickLDMRSDriver_Res1000:
250 ROS_WARN(
"Invalid flexres resolution %d! Setting to 32 (= 1 degree).", res);
251 res = SickLDMRSDriver_Res1000;
267 sick_ldmrs_msgs::ObjectArray oa;
268 oa.header.frame_id =
config_.frame_id;
271 oa.objects.resize(objects.size());
273 for (
int i = 0; i < objects.size(); i++)
275 oa.objects[i].id = objects[i].getObjectId();
278 oa.objects[i].velocity.twist.linear.x = objects[i].getAbsoluteVelocity().getX();
279 oa.objects[i].velocity.twist.linear.y = objects[i].getAbsoluteVelocity().getY();
280 oa.objects[i].velocity.twist.linear.x = objects[i].getAbsoluteVelocity().getX();
281 oa.objects[i].velocity.twist.linear.y = objects[i].getAbsoluteVelocity().getY();
282 oa.objects[i].velocity.covariance[0] = objects[i].getAbsoluteVelocitySigma().getX();
283 oa.objects[i].velocity.covariance[7] = objects[i].getAbsoluteVelocitySigma().getX();
285 oa.objects[i].bounding_box_center.position.x = objects[i].getBoundingBoxCenter().getX();
286 oa.objects[i].bounding_box_center.position.y = objects[i].getBoundingBoxCenter().getY();
287 oa.objects[i].bounding_box_size.x = objects[i].getBoundingBox().getX();
288 oa.objects[i].bounding_box_size.y = objects[i].getBoundingBox().getY();
290 oa.objects[i].object_box_center.pose.position.x = objects[i].getCenterPoint().getX();
291 oa.objects[i].object_box_center.pose.position.y = objects[i].getCenterPoint().getY();
293 oa.objects[i].object_box_center.covariance[0] = objects[i].getCenterPointSigma().getX();
294 oa.objects[i].object_box_center.covariance[7] = objects[i].getCenterPointSigma().getY();
295 oa.objects[i].object_box_center.covariance[35] = objects[i].getCourseAngleSigma();
296 oa.objects[i].object_box_size.x = objects[i].getObjectBox().getX();
297 oa.objects[i].object_box_size.y = objects[i].getObjectBox().getY();
299 datatypes::Polygon2D contour = objects[i].getContourPoints();
300 oa.objects[i].contour_points.resize(contour.size());
301 for (
int j = 0; j < contour.size(); j++)
303 oa.objects[i].contour_points[j].x = contour[j].getX();
304 oa.objects[i].contour_points[j].y = contour[j].getY();
315 devices::LDMRS* ldmrs;
316 ldmrs =
dynamic_cast<devices::LDMRS*
>(
manager_->getFirstDeviceByType(Sourcetype_LDMRS));
319 ROS_WARN(
"isUpsideDown: no connection to LDMRS!");
324 ldmrs->getParameter(devices::ParaUpsideDownMode, &code);
330 devices::LDMRS* ldmrs;
331 ldmrs =
dynamic_cast<devices::LDMRS*
>(
manager_->getFirstDeviceByType(Sourcetype_LDMRS));
334 ROS_WARN(
"printFlexResError: no connection to LDMRS!");
339 ldmrs->getParameter(devices::ParaDetailedError, &code);
341 ROS_ERROR(
"FlexRes detailed error: %s", msg.c_str());
354 devices::LDMRS* ldmrs;
355 ldmrs =
dynamic_cast<devices::LDMRS*
>(
manager_->getFirstDeviceByType(Sourcetype_LDMRS));
358 ROS_WARN(
"update_config: no connection to LDMRS!");
365 if (!ldmrs->setScanAngles(new_config.start_angle, new_config.end_angle))
366 ROS_WARN(
"Sending param not successful: ");
368 switch (
config_.scan_frequency)
370 case SickLDMRSDriver_ScanFreq1250:
373 case SickLDMRSDriver_ScanFreq2500:
376 case SickLDMRSDriver_ScanFreq5000:
385 ROS_WARN(
"Sending param not successful: ScanFrequency");
386 if (!ldmrs->setSyncAngleOffset(
config_.sync_angle_offset))
387 ROS_WARN(
"Sending param not successful: SyncAngleOffset");
388 if (!ldmrs->setParameter(devices::ParaContourPointDensity,
config_.contour_point_density))
389 ROS_WARN(
"Sending param not successful: ContourPointDensity");
390 if (!ldmrs->setParameter(devices::ParaMinimumObjectAge,
config_.min_object_age))
391 ROS_WARN(
"Sending param not successful: MinimumObjectAge");
392 if (!ldmrs->setParameter(devices::ParaMaximumPredictionAge,
config_.max_prediction_age))
393 ROS_WARN(
"Sending param not successful: MaximumPredictionAge");
394 if (!ldmrs->setParameter(devices::ParaRangeReduction,
config_.layer_range_reduction))
395 ROS_WARN(
"Sending param not successful: RangeReduction");
396 if (!ldmrs->setParameter(devices::ParaIgnoreNearRange,
config_.ignore_near_range ? 1 : 0))
397 ROS_WARN(
"Sending param not successful: IgnoreNearRange");
398 if (!ldmrs->setParameter(devices::ParaSensitivityControl,
config_.sensitivity_control ? 1 : 0))
399 ROS_WARN(
"Sending param not successful: SensitivityControl");
401 if (
config_.angular_resolution_type == SickLDMRSDriver_FlexRes)
403 std::vector<std::pair<int, int> > res_map, res_map_filtered;
404 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle1 * rad2deg * 32.0),
config_.flexres_resolution1));
405 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle2 * rad2deg * 32.0),
config_.flexres_resolution2));
406 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle3 * rad2deg * 32.0),
config_.flexres_resolution3));
407 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle4 * rad2deg * 32.0),
config_.flexres_resolution4));
408 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle5 * rad2deg * 32.0),
config_.flexres_resolution5));
409 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle6 * rad2deg * 32.0),
config_.flexres_resolution6));
410 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle7 * rad2deg * 32.0),
config_.flexres_resolution7));
411 res_map.push_back(std::pair<int, int>(round(
config_.flexres_start_angle8 * rad2deg * 32.0),
config_.flexres_resolution8));
414 for (
int i = 0; i < res_map.size() - 1; ++i)
416 if (res_map[i].first > res_map[i + 1].first)
418 res_map_filtered.push_back(res_map[i]);
421 if (res_map[7].first > (-1918))
423 res_map_filtered.push_back(res_map[7]);
427 int shots_per_scan = 0;
428 double sum_res0125 = 0;
429 for (
int i = 0; i < res_map_filtered.size() - 1; ++i)
432 double sector_angle = (res_map_filtered[i].first - res_map_filtered[i + 1].first) / 32.0;
434 shots_per_scan += sector_angle * 32.0 / res_map_filtered[i].second;
435 if (res_map_filtered[i].second == SickLDMRSDriver_Res0125)
437 sum_res0125 += sector_angle;
441 if (shots_per_scan > 440)
443 ROS_WARN(
"FlexRes: The number of shots per scan must be at most 440. Not updating FlexRes config!");
446 if (sum_res0125 > 20.0)
448 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!");
455 if (!ldmrs->setParameter(devices::ParaAngularResolutionType, SickLDMRSDriver_ConstantRes))
456 ROS_WARN(
"Sending param not successful: AngularResolutionType");
462 if (!ldmrs->setParameter(devices::ParaNumSectors, res_map_filtered.size()))
465 for (
int i = 0; i < res_map_filtered.size(); ++i)
468 if (!ldmrs->setParameter((devices::MrsParameterId)(0x4001 + i), res_map_filtered[i].first))
472 if (!ldmrs->setParameter((devices::MrsParameterId)(0x4009 + i), res_map_filtered[i].second))
478 if (!ldmrs->setParameter(devices::ParaAngularResolutionType,
config_.angular_resolution_type))
479 ROS_WARN(
"Sending param not successful: AngularResolutionType");
481 ROS_INFO(
"... done updating config.");
488 case devices::ErrFlexResNumShotsInvalid:
489 return "The number of shots per scan is higher than 440.";
490 case devices::ErrFlexResSizeOneEighthSectorInvalid:
491 return "The sectors with a resolution of 0.125 deg sum up to more than 20 deg.";
492 case devices::ErrFlexResFreqInvalid:
493 return "The scan frequency is not 12.5Hz.";
494 case devices::ErrFlexResSectorsOverlapping:
495 return "The start angles of the sectors decrease not strictly monotone.";
496 case devices::ErrFlexResScannerNotIdle:
497 return "Could not set FlexRes parameter because the sensor is in flex res mode and not idle.";
498 case devices::ErrFlexResResolutionInvalid:
499 return "The resolution of one sector is not 4, 8, 16 or 32 (0.125 deg, 0.25 deg, 0.5 deg, 1 deg).";
500 case devices::ErrFlexResNumSectorsInvalid:
501 return "The number of sectors is larger than 8.";
503 std::ostringstream ss;
504 ss <<
"UNKNOWN ERROR CODE (" << code <<
")";
512 int main(
int argc,
char **argv)
514 ros::init(argc, argv,
"sick_ldmrs_node");
516 = boost::make_shared<diagnostic_updater::Updater>();
532 ROS_INFO(
"Adding the application SickLDMRS.");
533 name =
"Sick LDMRS ROS Driver App";
537 app.setApplicationName(name);
539 result = manager.addApplication(&app,
id);
542 ROS_ERROR(
"Failed to add application %s, aborting!", name.c_str());
545 ROS_INFO(
"Application is running.");
555 ROS_INFO(
"Adding the LDMRS device.");
556 devices::LDMRS* ldmrs =
new devices::LDMRS(&manager);
557 ldmrs->setWeWantObjectData(
true);
558 std::string hostname;
560 nh.
param<std::string>(
"hostname", hostname,
"192.168.0.1");
561 ROS_INFO(
"Set IP address to %s", hostname.c_str());
562 ldmrs->setIpAddress(hostname);
565 result = manager.addAndRunDevice(ldmrs, name,
id);
568 ROS_ERROR(
"Failed to add device %s, aborting!", name.c_str());
572 std::string serial_number = ldmrs->getSerialNumber();
573 diagnostics->setHardwareID(serial_number);
575 ROS_INFO(
"LD-MRS Firmware version is %s", ldmrs->getFirmwareVersion().c_str());
586 diagnostics->update();
diagnostic_updater::DiagnosedPublisher< sensor_msgs::PointCloud2 > * diagnosticPub_
int main(int argc, char **argv)
SickLDMRS(Manager *manager, boost::shared_ptr< diagnostic_updater::Updater > diagnostics)
void publish(const boost::shared_ptr< M > &message) const
dynamic_reconfigure::Server< SickLDMRSDriverConfig > dynamic_reconfigure_server_
void summary(unsigned char lvl, const std::string s)
void setData(BasicData &data)
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void validate_flexres_resolution(int &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
void validate_config(SickLDMRSDriverConfig &conf)
boost::shared_ptr< diagnostic_updater::Updater > diagnostics_
std::string flexres_err_to_string(const UINT32 code) const
virtual void publish(const boost::shared_ptr< T > &message)
double expected_frequency_
void update_config(SickLDMRSDriverConfig &new_config, uint32_t level=0)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void validate_flexres_start_angle(double &angle1, double &angle2)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
void add(const std::string &key, const T &val)
ROSCPP_DECL void spinOnce()
void pubObjects(datatypes::ObjectList &objects)
ros::Publisher object_pub_
SickLDMRSDriverConfig config_