diff --git a/CHANGELOG.md b/CHANGELOG.md index 14c26f1e..e103e2bb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,6 +8,10 @@ features that will be removed in future versions **Removed** for deprecated feat ## Released ## +### v2.8.13 - Dynamical pointcloud transform and QoS configuration + - **Update** Dynamical configuration of an additional pointcloud transform by rosparam, #104 + - **Update** Configuration of ROS quality of service by launchfile, #101 + ### v2.8.11 - LMS 1xxx support - **Update** LMS 1xxx support with scan configuration (scan frequency and angular resolution for firmware 2.x) diff --git a/driver/src/ldmrs/sick_ldmrs_driver.cpp b/driver/src/ldmrs/sick_ldmrs_driver.cpp index f640f819..20d81ea1 100644 --- a/driver/src/ldmrs/sick_ldmrs_driver.cpp +++ b/driver/src/ldmrs/sick_ldmrs_driver.cpp @@ -55,7 +55,7 @@ #endif // Convert lmdrs scan to PointCloud2 -void ldmrsScanToPointCloud2(const datatypes::Scan* scan, const sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, bool isRearMirrorSide, const std::string& frame_id, ros_sensor_msgs::PointCloud2& msg, ros_sensor_msgs::PointCloud2& msg_polar); +void ldmrsScanToPointCloud2(const datatypes::Scan* scan, sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, bool isRearMirrorSide, const std::string& frame_id, ros_sensor_msgs::PointCloud2& msg, ros_sensor_msgs::PointCloud2& msg_polar); namespace sick_ldmrs_driver { @@ -610,7 +610,7 @@ std::string SickLDMRS::flexres_err_to_string(const UINT32 code) const } // namespace sick_ldmrs_driver // Convert lmdrs scan to PointCloud2 -void ldmrsScanToPointCloud2(const datatypes::Scan* scan, const sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, bool isRearMirrorSide, const std::string& frame_id, ros_sensor_msgs::PointCloud2& msg, ros_sensor_msgs::PointCloud2& msg_polar) +void ldmrsScanToPointCloud2(const datatypes::Scan* scan, sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, bool isRearMirrorSide, const std::string& frame_id, ros_sensor_msgs::PointCloud2& msg, ros_sensor_msgs::PointCloud2& msg_polar) { typedef struct SICK_LDMRS_Point { diff --git a/driver/src/sick_cloud_transform.cpp b/driver/src/sick_cloud_transform.cpp index f1891191..a96e63a0 100644 --- a/driver/src/sick_cloud_transform.cpp +++ b/driver/src/sick_cloud_transform.cpp @@ -72,25 +72,30 @@ sick_scan::SickCloudTransform::SickCloudTransform() sick_scan::SickCloudTransform::SickCloudTransform(rosNodePtr nh, bool cartesian_input_only) { + m_nh = nh; std::string add_transform_xyz_rpy = "0,0,0,0,0,0"; rosDeclareParam(nh, "add_transform_xyz_rpy", add_transform_xyz_rpy); rosGetParam(nh, "add_transform_xyz_rpy", add_transform_xyz_rpy); - if (!init(add_transform_xyz_rpy, cartesian_input_only)) + bool add_transform_check_dynamic_updates = false; + rosDeclareParam(nh, "add_transform_check_dynamic_updates", add_transform_check_dynamic_updates); + rosGetParam(nh, "add_transform_check_dynamic_updates", add_transform_check_dynamic_updates); + if (!init(add_transform_xyz_rpy, cartesian_input_only, add_transform_check_dynamic_updates)) { ROS_ERROR_STREAM("## ERROR SickCloudTransform(): Initialization by \"" << add_transform_xyz_rpy << "\" failed, use 6D pose \"x,y,z,roll,pitch,yaw\" in [m] resp. [rad]"); } } -sick_scan::SickCloudTransform::SickCloudTransform(const std::string& add_transform_xyz_rpy, bool cartesian_input_only) +sick_scan::SickCloudTransform::SickCloudTransform(rosNodePtr nh, const std::string& add_transform_xyz_rpy, bool cartesian_input_only, bool add_transform_check_dynamic_updates) { - if (!init(add_transform_xyz_rpy, cartesian_input_only)) + m_nh = nh; + if (!init(add_transform_xyz_rpy, cartesian_input_only, add_transform_check_dynamic_updates)) { ROS_ERROR_STREAM("## ERROR SickCloudTransform(): Initialization by \"" << add_transform_xyz_rpy << "\" failed, use 6D pose \"x,y,z,roll,pitch,yaw\" in [m] resp. [rad]"); } } // Initializes rotation matrix and translation vector from a 6D pose configuration (x,y,z,roll,pitch,yaw) in [m] resp. [rad] -bool sick_scan::SickCloudTransform::init(const std::string& add_transform_xyz_rpy, bool cartesian_input_only) +bool sick_scan::SickCloudTransform::init(const std::string& add_transform_xyz_rpy, bool cartesian_input_only, bool add_transform_check_dynamic_updates) { // Split string add_transform_xyz_rpy to 6D pose x,y,z,roll,pitch,yaw in [m] resp. [rad] std::istringstream config_stream(add_transform_xyz_rpy); @@ -98,7 +103,20 @@ bool sick_scan::SickCloudTransform::init(const std::string& add_transform_xyz_rp std::vector config_values; while (getline(config_stream, config_arg, ',')) { - config_values.push_back(std::stof(config_arg)); + // ROS-2 interpretes parameter values configured by "ros2 param set " as yaml content, + // but does not remove yaml escape characters required for negative numbers. Any '\\' is removed here. + std::string::size_type n = 0; + while ((n = config_arg.find('\\', n)) != std::string::npos) + config_arg.replace( n, 1, ""); + try + { + float arg_value = std::stof(config_arg); + config_values.push_back(arg_value); + } + catch(const std::exception& e) + { + ROS_ERROR_STREAM("## ERROR SickCloudTransform(): parse error in string \"" << add_transform_xyz_rpy << "\", arg=\"" << config_arg << "\", exception " << e.what()); + } } if(config_values.size() != 6) { @@ -136,9 +154,10 @@ bool sick_scan::SickCloudTransform::init(const std::string& add_transform_xyz_rp m_azimuth_offset = 0; } } - - // Configuration is given by 6D pose with P_world = T[world,cloud] * P_cloud. By applying the transform, we compute - + // Initialization successful + m_add_transform_xyz_rpy = add_transform_xyz_rpy; + m_cartesian_input_only = cartesian_input_only; + m_add_transform_check_dynamic_updates = add_transform_check_dynamic_updates; ROS_INFO_STREAM("SickCloudTransform: add_transform_xyz_rpy = (" << add_transform_xyz_rpy << ")"); ROS_INFO_STREAM("SickCloudTransform: azimuth_offset = " << (m_azimuth_offset * 180.0 / M_PI) << " [deg]"); ROS_INFO_STREAM("SickCloudTransform: additional 3x3 rotation matrix = { (" @@ -147,6 +166,7 @@ bool sick_scan::SickCloudTransform::init(const std::string& add_transform_xyz_rp << m_rotation_matrix[2][0] << "," << m_rotation_matrix[2][1] << "," << m_rotation_matrix[2][2] << ") }"); ROS_INFO_STREAM("SickCloudTransform: apply 3x3 rotation = " << (m_apply_3x3_rotation ? "true" : "false")); ROS_INFO_STREAM("SickCloudTransform: additional translation = (" << m_translation_vector[0] << "," << m_translation_vector[1] << "," << m_translation_vector[2] << ")"); + ROS_INFO_STREAM("SickCloudTransform: check_dynamic_updates = " << (m_add_transform_check_dynamic_updates ? "true" : "false")); return true; } diff --git a/driver/src/sick_generic_laser.cpp b/driver/src/sick_generic_laser.cpp index b3597e24..a5bd5e6c 100644 --- a/driver/src/sick_generic_laser.cpp +++ b/driver/src/sick_generic_laser.cpp @@ -93,7 +93,7 @@ #define SICK_GENERIC_MAJOR_VER "2" #define SICK_GENERIC_MINOR_VER "8" -#define SICK_GENERIC_PATCH_LEVEL "11" +#define SICK_GENERIC_PATCH_LEVEL "13" #define DELETE_PTR(p) if(p){delete(p);p=0;} diff --git a/driver/src/sick_scan_common.cpp b/driver/src/sick_scan_common.cpp index 9590dbec..6090b0f2 100644 --- a/driver/src/sick_scan_common.cpp +++ b/driver/src/sick_scan_common.cpp @@ -620,7 +620,7 @@ namespace sick_scan // add_transform_xyz_rpy := T[world,cloud] with parent "world" and child "cloud", i.e. P_world = T[world,cloud] * P_cloud // The additional transform applies to cartesian lidar pointclouds and visualization marker (fields) // It is NOT applied to polar pointclouds, radarscans, ldmrs objects or other messages - m_add_transform_xyz_rpy = sick_scan::SickCloudTransform(nh); + m_add_transform_xyz_rpy = sick_scan::SickCloudTransform(nh, false); } /*! diff --git a/driver/src/sick_scansegment_xd/config.cpp b/driver/src/sick_scansegment_xd/config.cpp index afef0d11..3f085e56 100644 --- a/driver/src/sick_scansegment_xd/config.cpp +++ b/driver/src/sick_scansegment_xd/config.cpp @@ -267,7 +267,9 @@ bool sick_scansegment_xd::Config::Init(rosNodePtr _node) // Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform) std::string str_add_transform_xyz_rpy = "0,0,0,0,0,0"; ROS_DECL_GET_PARAMETER(node, "add_transform_xyz_rpy", str_add_transform_xyz_rpy); - add_transform_xyz_rpy = sick_scan::SickCloudTransform(str_add_transform_xyz_rpy); + bool add_transform_check_dynamic_updates = false; + ROS_DECL_GET_PARAMETER(node, "add_transform_check_dynamic_updates", add_transform_check_dynamic_updates); + add_transform_xyz_rpy = sick_scan::SickCloudTransform(node, str_add_transform_xyz_rpy, false, add_transform_check_dynamic_updates); // Optional range filter float range_min = 0, range_max = 100; int range_filter_handling = 0; diff --git a/driver/src/sick_scansegment_xd/msgpack_parser.cpp b/driver/src/sick_scansegment_xd/msgpack_parser.cpp index 5fa2ee03..85d55029 100644 --- a/driver/src/sick_scansegment_xd/msgpack_parser.cpp +++ b/driver/src/sick_scansegment_xd/msgpack_parser.cpp @@ -506,7 +506,7 @@ std::string sick_scansegment_xd::MsgPackParser::MsgpackToHexDump(const std::vect * @param[in] verbose true: enable debug output, false: quiet mode */ bool sick_scansegment_xd::MsgPackParser::Parse(const std::vector& msgpack_data, fifo_timestamp msgpack_timestamp, - const sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, MsgPackParserOutput& result, + sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, MsgPackParserOutput& result, sick_scansegment_xd::MsgPackValidatorData& msgpack_validator_data_collector, const sick_scansegment_xd::MsgPackValidator& msgpack_validator, bool msgpack_validator_enabled, bool discard_msgpacks_not_validated, bool use_software_pll, bool verbose) @@ -563,7 +563,7 @@ bool sick_scansegment_xd::MsgPackParser::Parse(const std::vector& msgpa * @param[in] verbose true: enable debug output, false: quiet mode */ bool sick_scansegment_xd::MsgPackParser::Parse(std::istream& msgpack_istream, fifo_timestamp msgpack_timestamp, - const sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, MsgPackParserOutput& result, + sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, MsgPackParserOutput& result, sick_scansegment_xd::MsgPackValidatorData& msgpack_validator_data_collector, const sick_scansegment_xd::MsgPackValidator& msgpack_validator, bool msgpack_validator_enabled, bool discard_msgpacks_not_validated, @@ -751,7 +751,9 @@ bool sick_scansegment_xd::MsgPackParser::Parse(std::istream& msgpack_istream, fi assert(iPointCount == channelTheta.data().size() && iPointCount == distValues[echoIdx].data().size() && iPointCount == rssiValues[echoIdx].data().size()); groupData.push_back(sick_scansegment_xd::MsgPackParserOutput::Scanline()); sick_scansegment_xd::MsgPackParserOutput::Scanline& scanline = groupData.back(); - scanline.reserve(iPointCount); + scanline.points.reserve(iPointCount); + scanline.range_min = +FLT_MAX; + scanline.range_max = -FLT_MAX; for (int pointIdx = 0; pointIdx < iPointCount; pointIdx++) { float dist = 0.001f * distValues[echoIdx].data()[pointIdx]; // convert distance to meter @@ -762,16 +764,28 @@ bool sick_scansegment_xd::MsgPackParser::Parse(std::istream& msgpack_istream, fi float y = dist * sin_azimuth[pointIdx] * cos_elevation; float z = dist * sin_elevation; add_transform_xyz_rpy.applyTransform(x, y, z); - float azimuth = channelTheta.data()[pointIdx]; + float azimuth = channelTheta.data()[pointIdx]; float azimuth_norm = normalizeAngle(azimuth); if (msgpack_validator_enabled) { msgpack_validator_data.update(echoIdx, segment_idx, azimuth_norm, elevation); msgpack_validator_data_collector.update(echoIdx, segment_idx, azimuth_norm, elevation); } - scanline.push_back(sick_scansegment_xd::MsgPackParserOutput::LidarPoint(x, y, z, intensity, dist, azimuth, elevation, groupIdx, echoIdx, pointIdx)); + scanline.range_min = std::min(dist, scanline.range_min); + scanline.range_max = std::min(dist, scanline.range_max); + scanline.points.push_back(sick_scansegment_xd::MsgPackParserOutput::LidarPoint(x, y, z, intensity, dist, azimuth, elevation, groupIdx, echoIdx, pointIdx)); } } + if (iPointCount > 0) + { + scanline.angle_min = normalizeAngle(scanline.points.front().azimuth); + scanline.angle_max = normalizeAngle(scanline.points.back().azimuth); + scanline.angle_increment = (scanline.angle_max - scanline.angle_min) / (float)iPointCount; + } + else + { + scanline = sick_scansegment_xd::MsgPackParserOutput::Scanline(); + } } // debug output @@ -888,7 +902,7 @@ bool sick_scansegment_xd::MsgPackParser::WriteCSV(const std::vector& scanline = result.scandata[groupIdx].scanlines[echoIdx]; + const std::vector& scanline = result.scandata[groupIdx].scanlines[echoIdx].points; for (int pointIdx = 0; pointIdx < scanline.size(); pointIdx++) { const sick_scansegment_xd::MsgPackParserOutput::LidarPoint& point = scanline[pointIdx]; @@ -927,7 +941,7 @@ bool sick_scansegment_xd::MsgPackParser::ExportXYZI(const std::vector& scanline = result.scandata[groupIdx].scanlines[echoIdx]; + const std::vector& scanline = result.scandata[groupIdx].scanlines[echoIdx].points; for (int pointIdx = 0; pointIdx < scanline.size(); pointIdx++) { const sick_scansegment_xd::MsgPackParserOutput::LidarPoint& point = scanline[pointIdx]; diff --git a/driver/src/sick_scansegment_xd/ros_msgpack_publisher.cpp b/driver/src/sick_scansegment_xd/ros_msgpack_publisher.cpp index 2baeb051..739b53c6 100644 --- a/driver/src/sick_scansegment_xd/ros_msgpack_publisher.cpp +++ b/driver/src/sick_scansegment_xd/ros_msgpack_publisher.cpp @@ -68,7 +68,7 @@ * config.publish_frame_id: frame id of ros PointCloud2 messages, default: "world" * @param[in] qos quality of service profile for the ros publisher, default: 1 */ -sick_scansegment_xd::RosMsgpackPublisher::RosMsgpackPublisher(const std::string& node_name, const sick_scansegment_xd::Config& config, const rosQoS& qos) +sick_scansegment_xd::RosMsgpackPublisher::RosMsgpackPublisher(const std::string& node_name, const sick_scansegment_xd::Config& config, rosQoS qos) #if defined __ROS_VERSION && __ROS_VERSION > 1 : Node(node_name) #endif @@ -82,12 +82,23 @@ sick_scansegment_xd::RosMsgpackPublisher::RosMsgpackPublisher(const std::string& m_min_azimuth = (float)-M_PI; m_max_azimuth = (float)+M_PI; #if defined __ROS_VERSION && __ROS_VERSION > 1 // ROS-2 publisher + QoSConverter qos_converter; + int qos_val = -1; + rosDeclareParam(m_node, "ros_qos", qos_val); + rosGetParam(m_node, "ros_qos", qos_val); + if (qos_val >= 0) + qos = qos_converter.convert(qos_val); m_points_collector = SegmentPointsCollector(m_segment_count); if(m_publish_topic != "") m_publisher_cur_segment = create_publisher(m_publish_topic, qos); if(m_publish_topic_all_segments != "") m_publisher_all_segments = create_publisher(m_publish_topic_all_segments, qos); #elif defined __ROS_VERSION && __ROS_VERSION > 0 // ROS-1 publisher + int qos_val = -1; + rosDeclareParam(m_node, "ros_qos", qos_val); + rosGetParam(m_node, "ros_qos", qos_val); + if (qos_val >= 0) + qos = qos_val; if(m_publish_topic != "") m_publisher_cur_segment = m_node->advertise(m_publish_topic, qos); if(m_publish_topic_all_segments != "") @@ -210,8 +221,8 @@ void sick_scansegment_xd::RosMsgpackPublisher::HandleMsgPackData(const sick_scan echo_count = std::max(msgpack_data.scandata[groupIdx].scanlines.size(), echo_count); for (int echoIdx = 0; echoIdx < msgpack_data.scandata[groupIdx].scanlines.size(); echoIdx++) { - total_point_count += msgpack_data.scandata[groupIdx].scanlines[echoIdx].size(); - point_count_per_echo = std::max(msgpack_data.scandata[groupIdx].scanlines[echoIdx].size(), point_count_per_echo); + total_point_count += msgpack_data.scandata[groupIdx].scanlines[echoIdx].points.size(); + point_count_per_echo = std::max(msgpack_data.scandata[groupIdx].scanlines[echoIdx].points.size(), point_count_per_echo); } } float lidar_points_min_azimuth = +2.0f * (float)M_PI, lidar_points_max_azimuth = -2.0f * (float)M_PI; @@ -224,7 +235,7 @@ void sick_scansegment_xd::RosMsgpackPublisher::HandleMsgPackData(const sick_scan { for (int echoIdx = 0; echoIdx < msgpack_data.scandata[groupIdx].scanlines.size(); echoIdx++) { - const std::vector& scanline = msgpack_data.scandata[groupIdx].scanlines[echoIdx]; + const std::vector& scanline = msgpack_data.scandata[groupIdx].scanlines[echoIdx].points; for (int pointIdx = 0; pointIdx < scanline.size(); pointIdx++) { const sick_scansegment_xd::MsgPackParserOutput::LidarPoint& point = scanline[pointIdx]; diff --git a/include/sick_scan/sick_cloud_transform.h b/include/sick_scan/sick_cloud_transform.h index c64dd391..224e2e40 100644 --- a/include/sick_scan/sick_cloud_transform.h +++ b/include/sick_scan/sick_cloud_transform.h @@ -87,8 +87,8 @@ namespace sick_scan public: SickCloudTransform(); - SickCloudTransform(rosNodePtr nh, bool cartesian_input_only = false); - SickCloudTransform(const std::string& add_transform_xyz_rpy, bool cartesian_input_only = false); + SickCloudTransform(rosNodePtr nh, bool cartesian_input_only /* = false */); + SickCloudTransform(rosNodePtr nh, const std::string& add_transform_xyz_rpy, bool cartesian_input_only /* = false */, bool add_transform_check_dynamic_updates /* = false */); /* * Apply an optional transform to point (x, y, z). @@ -97,8 +97,22 @@ namespace sick_scan * @param[in+out] y input y in child coordinates, output y in parent coordinates * @param[in+out] z input z in child coordinates, output z in parent coordinates */ - template inline void applyTransform(float_type& x, float_type& y, float_type& z) const // + template inline void applyTransform(float_type& x, float_type& y, float_type& z) { + // Check parameter and re-init if parameter "add_transform_xyz_rpy" changed + if (m_add_transform_check_dynamic_updates && m_nh) + { + std::string add_transform_xyz_rpy = m_add_transform_xyz_rpy; + rosGetParam(m_nh, "add_transform_xyz_rpy", add_transform_xyz_rpy); + if (m_add_transform_xyz_rpy != add_transform_xyz_rpy) + { + if (!init(add_transform_xyz_rpy, m_cartesian_input_only, m_add_transform_check_dynamic_updates)) + { + ROS_ERROR_STREAM("## ERROR SickCloudTransform(): Re-Initialization by \"" << add_transform_xyz_rpy << "\" failed, use 6D pose \"x,y,z,roll,pitch,yaw\" in [m] resp. [rad]"); + } + } + } + // Apply transform if (m_apply_3x3_rotation) { float_type u = x * m_rotation_matrix[0][0] + y * m_rotation_matrix[0][1] + z * m_rotation_matrix[0][2]; @@ -127,7 +141,7 @@ namespace sick_scan typedef std::array, 3> Matrix3x3; // 3x3 rotation matrix // Initializes rotation matrix and translation vector from a 6D pose configuration (x,y,z,roll,pitch,yaw) in [m] resp. [rad] - bool init(const std::string& add_transform_xyz_rpy, bool cartesian_input_only); + bool init(const std::string& add_transform_xyz_rpy, bool cartesian_input_only, bool add_transform_check_dynamic_updates); // Converts roll (rotation about X), pitch (rotation about Y), yaw (rotation about Z) to 3x3 rotation matrix static Matrix3x3 eulerToRot3x3(float roll, float pitch, float yaw); @@ -135,6 +149,10 @@ namespace sick_scan // Multiply two 3x3 matrices, return a * b static Matrix3x3 multiply3x3(const Matrix3x3& a, const Matrix3x3& b); + rosNodePtr m_nh = 0; // ros node handle + std::string m_add_transform_xyz_rpy = ""; // currently configured ros parameter "add_transform_xyz_rpy" + bool m_add_transform_check_dynamic_updates = false; // True: ros parameter "add_transform_xyz_rpy" can be updated during runtime by "rosparam set", False: parameter "add_transform_xyz_rpy" configured by launchfile only + bool m_cartesian_input_only = false; // currently configured parameter cartesian_input_only bool m_apply_3x3_rotation = false; // true, if the 3x3 rotation_matrix has to be applied, otherwise false (default) Vector3D m_translation_vector = { 0, 0, 0 }; // translational part x,y,z of the 6D pose, default: 0 Matrix3x3 m_rotation_matrix = { 1, 0, 0, 0, 1, 0, 0, 0, 1 }; // rotational part roll,pitch,yaw by 3x3 rotation matrix, default: 3x3 identity diff --git a/include/sick_scan/sick_ros_wrapper.h b/include/sick_scan/sick_ros_wrapper.h index 70a584bd..e99b78f0 100644 --- a/include/sick_scan/sick_ros_wrapper.h +++ b/include/sick_scan/sick_ros_wrapper.h @@ -169,12 +169,17 @@ template class rosPublisher : public ros::Publisher }; template rosPublisher rosAdvertise(rosNodePtr nh, const std::string& topic, uint32_t queue_size = 10, rosQoS qos = 10) { + int qos_val = -1; + rosDeclareParam(nh, "ros_qos", qos_val); + rosGetParam(nh, "ros_qos", qos_val); + if (qos_val >= 0) + qos = qos_val; std::string topic2; if(topic.empty() || topic[0] != '/') topic2 = std::string("/") + topic; else topic2 = topic; - ROS_INFO_STREAM("Publishing on topic \"" << topic2 << "\""); + ROS_INFO_STREAM("Publishing on topic \"" << topic2 << "\", qos=" << qos); ros::Publisher publisher = nh->advertise(topic2, queue_size); return rosPublisher(publisher); } @@ -300,6 +305,27 @@ inline uint32_t sec(const rosDuration& time) { return (uint32_t)(time.nanosecond inline uint32_t nsec(const rosDuration& time) { return (uint32_t)(time.nanoseconds() - 1000000000 * sec(time)); } // return nanoseconds part of rclcpp::Duration inline uint64_t rosNanosecTimestampNow(void) { rosTime now = rosTimeNow(); return (((uint64_t)sec(now)) * (uint64_t)1000000000) + std::min((uint64_t)nsec(now), (uint64_t)1000000000); } +class QoSConverter +{ +public: + int convert(const rosQoS& qos) const + { + for (std::map::const_iterator qos_iter = m_qos_map.cbegin(); qos_iter != m_qos_map.cend(); qos_iter++) + if (qos_iter->second == qos) + return qos_iter->first; + return 0; + } + rosQoS convert(const int& qos) const + { + for (std::map::const_iterator qos_iter = m_qos_map.cbegin(); qos_iter != m_qos_map.cend(); qos_iter++) + if (qos_iter->first == qos) + return qos_iter->second; + return rclcpp::SystemDefaultsQoS(); + } +protected: + std::map m_qos_map = { {0, rclcpp::SystemDefaultsQoS()}, {1, rclcpp::ParameterEventsQoS()}, {2, rclcpp::ServicesQoS()}, {3, rclcpp::ParametersQoS()}, {4, rclcpp::SensorDataQoS()} }; +}; + template class rosPublisher : public rclcpp::Publisher::SharedPtr { public: @@ -308,7 +334,13 @@ template class rosPublisher : public rclcpp::Publisher::SharedPtr }; template rosPublisher rosAdvertise(rosNodePtr nh, const std::string& topic, uint32_t queue_size = 10, rosQoS qos = rclcpp::SystemDefaultsQoS()) { - ROS_INFO_STREAM("Publishing on topic \"" << topic << "\""); + QoSConverter qos_converter; + int qos_val = -1; + rosDeclareParam(nh, "ros_qos", qos_val); + rosGetParam(nh, "ros_qos", qos_val); + if (qos_val >= 0) + qos = qos_converter.convert(qos_val); + ROS_INFO_STREAM("Publishing on topic \"" << topic << "\", qos=" << qos_converter.convert(qos)); auto publisher = nh->create_publisher(topic, qos); return rosPublisher(publisher); } diff --git a/include/sick_scansegment_xd/msgpack_parser.h b/include/sick_scansegment_xd/msgpack_parser.h index d4bd69b7..e8711ab3 100644 --- a/include/sick_scansegment_xd/msgpack_parser.h +++ b/include/sick_scansegment_xd/msgpack_parser.h @@ -125,7 +125,16 @@ namespace sick_scansegment_xd /* * @brief type Scanline is a vector of LidarPoint data. multiScan136 transmits 3 echos, each echo is a Scanline. */ - typedef std::vector Scanline; + class Scanline + { + public: + std::vector points; // list of all scan points + float angle_min = 0; // start angle of the scan [rad] + float angle_max = 0; // end angle of the scan [rad] + float angle_increment = 0; // angular distance between measurements [rad] + float range_min = 0; // minimum range value [m] + float range_max = 0; // maximum range value [m] + }; /* * @brief type Scangroup is a vector of Scanlines. multiScan136 transmits 16 groups, each group has 3 echos (3 scanlines). @@ -140,7 +149,6 @@ namespace sick_scansegment_xd uint32_t timestampStop_nsec; std::vector scanlines; }; - // typedef std::vector Scangroup; /* * @brief scandata contains all data of a MsgPack. @@ -196,7 +204,7 @@ namespace sick_scansegment_xd * @param[in] use_software_pll true (default): result timestamp from sensor ticks by software pll, false: result timestamp from msg receiving * @param[in] verbose true: enable debug output, false: quiet mode */ - static bool Parse(const std::vector& msgpack_data, fifo_timestamp msgpack_timestamp, const sick_scan::SickCloudTransform& add_transform_xyz_rpy, + static bool Parse(const std::vector& msgpack_data, fifo_timestamp msgpack_timestamp, sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, MsgPackParserOutput& result, sick_scansegment_xd::MsgPackValidatorData& msgpack_validator_data_collector, const sick_scansegment_xd::MsgPackValidator& msgpack_validator = sick_scansegment_xd::MsgPackValidator(), bool msgpack_validator_enabled = false, bool discard_msgpacks_not_validated = false, @@ -239,7 +247,7 @@ namespace sick_scansegment_xd * @param[in] use_software_pll true (default): result timestamp from sensor ticks by software pll, false: result timestamp from msg receiving * @param[in] verbose true: enable debug output, false: quiet mode */ - static bool Parse(std::istream& msgpack_istream, fifo_timestamp msgpack_timestamp, const sick_scan::SickCloudTransform& add_transform_xyz_rpy, + static bool Parse(std::istream& msgpack_istream, fifo_timestamp msgpack_timestamp, sick_scan::SickCloudTransform& add_transform_xyz_rpy, sick_scan::SickRangeFilter& range_filter, MsgPackParserOutput& result, sick_scansegment_xd::MsgPackValidatorData& msgpack_validator_data_collector, const sick_scansegment_xd::MsgPackValidator& msgpack_validator = sick_scansegment_xd::MsgPackValidator(), diff --git a/include/sick_scansegment_xd/ros_msgpack_publisher.h b/include/sick_scansegment_xd/ros_msgpack_publisher.h index d14d354b..59d71cd2 100644 --- a/include/sick_scansegment_xd/ros_msgpack_publisher.h +++ b/include/sick_scansegment_xd/ros_msgpack_publisher.h @@ -103,7 +103,7 @@ namespace sick_scansegment_xd * config.publish_frame_id: frame id of ros PointCloud2 messages, default: "world" * @param[in] qos quality of service profile for the ros publisher, default: 1 */ - RosMsgpackPublisher(const std::string& node_name = "sick_scansegment_xd", const sick_scansegment_xd::Config& config = sick_scansegment_xd::Config(), const rosQoS& qos = 1); + RosMsgpackPublisher(const std::string& node_name = "sick_scansegment_xd", const sick_scansegment_xd::Config& config = sick_scansegment_xd::Config(), rosQoS qos = 1); /* * @brief RosMsgpackPublisher destructor diff --git a/launch/sick_ldmrs.launch b/launch/sick_ldmrs.launch index e5fa31e3..7e38c103 100644 --- a/launch/sick_ldmrs.launch +++ b/launch/sick_ldmrs.launch @@ -8,6 +8,7 @@ + @@ -47,6 +48,7 @@ + @@ -88,5 +90,13 @@ + + + + + + + + diff --git a/launch/sick_lms_1xx.launch b/launch/sick_lms_1xx.launch index ce6a7919..a905d52f 100644 --- a/launch/sick_lms_1xx.launch +++ b/launch/sick_lms_1xx.launch @@ -8,6 +8,7 @@ + @@ -61,6 +62,7 @@ + @@ -68,5 +70,13 @@ + + + + + + + + diff --git a/launch/sick_lms_1xx_encoder.launch b/launch/sick_lms_1xx_encoder.launch index aca6db61..2e9cd668 100644 --- a/launch/sick_lms_1xx_encoder.launch +++ b/launch/sick_lms_1xx_encoder.launch @@ -6,6 +6,7 @@ + @@ -56,6 +57,7 @@ + @@ -64,5 +66,13 @@ + + + + + + + + diff --git a/launch/sick_lms_1xxx.launch b/launch/sick_lms_1xxx.launch index 353e319f..5d72a867 100644 --- a/launch/sick_lms_1xxx.launch +++ b/launch/sick_lms_1xxx.launch @@ -7,6 +7,7 @@ + @@ -62,6 +63,7 @@ + @@ -74,5 +76,13 @@ + + + + + + + + diff --git a/launch/sick_lms_1xxx_v2.launch b/launch/sick_lms_1xxx_v2.launch index 933dedaa..19479ceb 100644 --- a/launch/sick_lms_1xxx_v2.launch +++ b/launch/sick_lms_1xxx_v2.launch @@ -7,6 +7,7 @@ + @@ -67,6 +68,7 @@ + @@ -79,5 +81,13 @@ + + + + + + + + diff --git a/launch/sick_lms_4xxx.launch b/launch/sick_lms_4xxx.launch index e6a35dcf..6d34997f 100644 --- a/launch/sick_lms_4xxx.launch +++ b/launch/sick_lms_4xxx.launch @@ -28,6 +28,7 @@ + @@ -85,6 +86,7 @@ + @@ -97,6 +99,14 @@ + + + + + + + + diff --git a/launch/sick_lms_4xxx_encoder.launch b/launch/sick_lms_4xxx_encoder.launch index fa48f564..e83ce6c9 100644 --- a/launch/sick_lms_4xxx_encoder.launch +++ b/launch/sick_lms_4xxx_encoder.launch @@ -23,6 +23,7 @@ + @@ -82,6 +83,7 @@ + @@ -90,6 +92,14 @@ + + + + + + + + diff --git a/launch/sick_lms_5xx.launch b/launch/sick_lms_5xx.launch index a8d4b422..f7745711 100644 --- a/launch/sick_lms_5xx.launch +++ b/launch/sick_lms_5xx.launch @@ -16,6 +16,7 @@ Check IP-address, if you scanner is not found after roslaunch. + @@ -80,6 +81,7 @@ Check IP-address, if you scanner is not found after roslaunch. + @@ -92,6 +94,14 @@ Check IP-address, if you scanner is not found after roslaunch. + + + + + + + + @@ -73,6 +74,7 @@ Check IP-address, if you scanner is not found after roslaunch. + @@ -81,6 +83,14 @@ Check IP-address, if you scanner is not found after roslaunch. + + + + + + + + @@ -54,6 +55,7 @@ + @@ -62,6 +64,14 @@ + + + + + + + + @@ -52,6 +53,7 @@ + @@ -60,6 +62,14 @@ + + + + + + + + @@ -61,6 +62,7 @@ + @@ -76,5 +78,13 @@ + + + + + + + + diff --git a/launch/sick_mrs_1xxx.launch b/launch/sick_mrs_1xxx.launch index dec58da8..3616443d 100644 --- a/launch/sick_mrs_1xxx.launch +++ b/launch/sick_mrs_1xxx.launch @@ -16,6 +16,7 @@ default max_angle for this scanner type is +137.5 degree. + @@ -70,6 +71,7 @@ default max_angle for this scanner type is +137.5 degree. + @@ -82,6 +84,14 @@ default max_angle for this scanner type is +137.5 degree. + + + + + + + + @@ -69,6 +70,7 @@ default max_angle for this scanner type is +137.5 degree. + @@ -77,6 +79,14 @@ default max_angle for this scanner type is +137.5 degree. + + + + + + + + @@ -61,6 +62,7 @@ + @@ -69,5 +71,13 @@ + + + + + + + + diff --git a/launch/sick_mrs_6xxx_first_echo.launch b/launch/sick_mrs_6xxx_first_echo.launch index 5ac8e1bc..3a06f25a 100644 --- a/launch/sick_mrs_6xxx_first_echo.launch +++ b/launch/sick_mrs_6xxx_first_echo.launch @@ -6,6 +6,7 @@ + @@ -58,6 +59,7 @@ + @@ -66,5 +68,13 @@ + + + + + + + + diff --git a/launch/sick_mrs_6xxx_last_echo.launch b/launch/sick_mrs_6xxx_last_echo.launch index 3058b085..f8bc5756 100644 --- a/launch/sick_mrs_6xxx_last_echo.launch +++ b/launch/sick_mrs_6xxx_last_echo.launch @@ -6,6 +6,7 @@ + @@ -57,6 +58,7 @@ + @@ -65,5 +67,13 @@ + + + + + + + + diff --git a/launch/sick_mrs_6xxx_narrow.launch b/launch/sick_mrs_6xxx_narrow.launch index c406f4be..3a2bab93 100644 --- a/launch/sick_mrs_6xxx_narrow.launch +++ b/launch/sick_mrs_6xxx_narrow.launch @@ -6,6 +6,7 @@ + @@ -59,6 +60,7 @@ + @@ -67,5 +69,13 @@ + + + + + + + + diff --git a/launch/sick_nav_2xx.launch b/launch/sick_nav_2xx.launch index de5af77c..09cedce6 100644 --- a/launch/sick_nav_2xx.launch +++ b/launch/sick_nav_2xx.launch @@ -6,6 +6,7 @@ + @@ -45,6 +46,7 @@ + @@ -53,5 +55,13 @@ + + + + + + + + diff --git a/launch/sick_nav_3xx.launch b/launch/sick_nav_3xx.launch index 243110c7..cb2319ff 100644 --- a/launch/sick_nav_3xx.launch +++ b/launch/sick_nav_3xx.launch @@ -12,6 +12,7 @@ + @@ -63,6 +64,7 @@ + @@ -71,6 +73,14 @@ + + + + + + + + diff --git a/launch/sick_nav_3xx_ascii.launch b/launch/sick_nav_3xx_ascii.launch index 1b047281..1aa6bb24 100644 --- a/launch/sick_nav_3xx_ascii.launch +++ b/launch/sick_nav_3xx_ascii.launch @@ -6,6 +6,7 @@ + @@ -48,6 +49,15 @@ + + + + + + + + + diff --git a/launch/sick_new_ip.launch b/launch/sick_new_ip.launch index 57db43a4..c5cfaa32 100644 --- a/launch/sick_new_ip.launch +++ b/launch/sick_new_ip.launch @@ -30,6 +30,14 @@ + + + + + + + + diff --git a/launch/sick_oem_15xx.launch b/launch/sick_oem_15xx.launch index 4567547d..7f26441a 100644 --- a/launch/sick_oem_15xx.launch +++ b/launch/sick_oem_15xx.launch @@ -12,6 +12,7 @@ + @@ -53,6 +54,7 @@ + @@ -61,6 +63,14 @@ + + + + + + + + @@ -55,6 +56,7 @@ + @@ -63,5 +65,13 @@ + + + + + + + + diff --git a/launch/sick_rms_1xxx_ascii.launch b/launch/sick_rms_1xxx_ascii.launch index fb5a3950..6dadef1f 100644 --- a/launch/sick_rms_1xxx_ascii.launch +++ b/launch/sick_rms_1xxx_ascii.launch @@ -6,6 +6,7 @@ + @@ -52,6 +53,7 @@ + @@ -60,5 +62,13 @@ + + + + + + + + diff --git a/launch/sick_rms_2xxx.launch b/launch/sick_rms_2xxx.launch index 48cc39c2..1b1abd6c 100644 --- a/launch/sick_rms_2xxx.launch +++ b/launch/sick_rms_2xxx.launch @@ -12,6 +12,7 @@ + @@ -59,6 +60,7 @@ + @@ -67,5 +69,13 @@ + + + + + + + + diff --git a/launch/sick_rms_3xx.launch b/launch/sick_rms_3xx.launch index 3e1ddf41..ab0a4887 100644 --- a/launch/sick_rms_3xx.launch +++ b/launch/sick_rms_3xx.launch @@ -12,6 +12,7 @@ + @@ -59,6 +60,7 @@ + @@ -67,5 +69,13 @@ + + + + + + + + diff --git a/launch/sick_rms_3xx_emul.launch b/launch/sick_rms_3xx_emul.launch index a6690c86..d5361fae 100644 --- a/launch/sick_rms_3xx_emul.launch +++ b/launch/sick_rms_3xx_emul.launch @@ -11,6 +11,7 @@ + @@ -47,6 +48,7 @@ + @@ -55,5 +57,13 @@ + + + + + + + + diff --git a/launch/sick_scansegment_xd.launch b/launch/sick_scansegment_xd.launch index dfe843ff..0533e1ce 100644 --- a/launch/sick_scansegment_xd.launch +++ b/launch/sick_scansegment_xd.launch @@ -10,6 +10,7 @@ + @@ -59,6 +60,7 @@ + @@ -90,6 +92,14 @@ + + + + + + + + diff --git a/launch/sick_tim_240.launch b/launch/sick_tim_240.launch index 561f7980..6affc29c 100644 --- a/launch/sick_tim_240.launch +++ b/launch/sick_tim_240.launch @@ -23,6 +23,7 @@ + @@ -67,6 +68,7 @@ + @@ -75,5 +77,13 @@ + + + + + + + + diff --git a/launch/sick_tim_240_bin.launch b/launch/sick_tim_240_bin.launch index e62a6d34..3d585c9d 100644 --- a/launch/sick_tim_240_bin.launch +++ b/launch/sick_tim_240_bin.launch @@ -21,6 +21,7 @@ + @@ -65,6 +66,7 @@ + @@ -73,5 +75,13 @@ + + + + + + + + diff --git a/launch/sick_tim_4xx.launch b/launch/sick_tim_4xx.launch index cdbf4cb0..e11ca732 100644 --- a/launch/sick_tim_4xx.launch +++ b/launch/sick_tim_4xx.launch @@ -49,6 +49,7 @@ + @@ -90,6 +91,7 @@ + @@ -98,6 +100,14 @@ + + + + + + + + diff --git a/launch/sick_tim_5xx.launch b/launch/sick_tim_5xx.launch index 4539b30c..d0437c5f 100644 --- a/launch/sick_tim_5xx.launch +++ b/launch/sick_tim_5xx.launch @@ -26,6 +26,7 @@ + @@ -67,6 +68,7 @@ + @@ -75,6 +77,14 @@ + + + + + + + + @@ -76,6 +77,16 @@ + + + + + + + + + + @@ -56,6 +57,7 @@ + @@ -64,6 +66,14 @@ + + + + + + + + diff --git a/launch/sick_tim_5xx_twin.launch b/launch/sick_tim_5xx_twin.launch index f4d70d29..40cfd921 100644 --- a/launch/sick_tim_5xx_twin.launch +++ b/launch/sick_tim_5xx_twin.launch @@ -18,6 +18,7 @@ + @@ -58,6 +59,7 @@ + @@ -66,6 +68,14 @@ + + + + + + + + @@ -94,6 +104,14 @@ + + + + + + + + diff --git a/launch/sick_tim_7xx.launch b/launch/sick_tim_7xx.launch index 3d2ded6d..a89e05e2 100644 --- a/launch/sick_tim_7xx.launch +++ b/launch/sick_tim_7xx.launch @@ -26,6 +26,7 @@ + @@ -69,6 +70,7 @@ + @@ -76,6 +78,14 @@ + + + + + + + + diff --git a/launch/sick_tim_7xxS.launch b/launch/sick_tim_7xxS.launch index 43f8e240..12916d86 100644 --- a/launch/sick_tim_7xxS.launch +++ b/launch/sick_tim_7xxS.launch @@ -27,6 +27,7 @@ + @@ -71,6 +72,7 @@ + @@ -78,6 +80,14 @@ + + + + + + + +