Go to the documentation of this file.
39 #ifndef SICK_LDMRS800001S01_H_
40 #define SICK_LDMRS800001S01_H_
58 #include <sick_ldmrs/manager.hpp>
59 #include <sick_ldmrs/application/BasicApplication.hpp>
60 #include <sick_ldmrs/datatypes/Object.hpp>
62 #if __ROS_VERSION == 2 // ROS-2 (Linux or Windows)
63 #include <sick_scan_xd/msg/sick_ldmrs_object_array.hpp>
64 #include <diagnostic_updater/diagnostic_updater.hpp>
65 #include <diagnostic_updater/publisher.hpp>
87 template <
typename MessageType>
void publish(
const std::shared_ptr<MessageType> & message)
92 template <
typename MessageType>
void publish(
const MessageType & message)
104 SickLDMRS(
rosNodePtr nh, Manager* manager, std::shared_ptr<diagnostic_updater::Updater> diagnostics);
110 #if defined USE_DYNAMIC_RECONFIGURE && __ROS_VERSION == 1
111 void update_config_cb(sick_scan_xd::SickLDMRSDriverConfig &new_config, uint32_t level = 0);
113 #if defined USE_DYNAMIC_RECONFIGURE && __ROS_VERSION == 2
114 rcl_interfaces::msg::SetParametersResult update_config_cb(
const std::vector<rclcpp::Parameter> ¶meters);
116 void pubObjects(datatypes::ObjectList &objects);
138 #if defined USE_DYNAMIC_RECONFIGURE && __ROS_VERSION == 1
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy
DiagnosedPublishAdapter< rosPublisher< ros_sensor_msgs::PointCloud2 > > * diagnosticPub_
std::shared_ptr< diagnostic_updater::Updater > diagnostics_
A structure that holds the constructor parameters for the TimeStampStatus class.
void publish(const std::shared_ptr< MessageType > &message)
SickLDMRS(rosNodePtr nh, Manager *manager, std::shared_ptr< diagnostic_updater::Updater > diagnostics)
void validate_flexres_resolution(int &res)
std::string rosTopicName(rosPublisher< T > &publisher)
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
TopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
sick_scan_xd::SickRangeFilter m_range_filter
void pubObjects(datatypes::ObjectList &objects)
void update_config(SickLDMRSDriverConfig &new_config, uint32_t level=0)
def message(msg, *args, **kwargs)
void setData(BasicData &data)
rosPublisher< sick_scan_msg::SickLdmrsObjectArray > object_pub_
void rosPublish(rosPublisher< T > &publisher, const T &msg)
void publish(const MessageType &message)
A class to facilitate making diagnostics for a topic using a FrequencyStatus and TimeStampStatus.
DiagnosedPublishAdapter(PublisherType publisher, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
double expected_frequency_
void validate_config(SickLDMRSDriverConfig &conf)
rosPublisher< ros_sensor_msgs::PointCloud2 > pub_
Wrapper for the diagnostic_msgs::msg::DiagnosticStatus message that makes it easier to update.
virtual ~DiagnosedPublishAdapter()
std::string cloud_topic_val
SickLDMRSDriverConfig config_
std::string flexres_err_to_string(const UINT32 code) const
void validate_flexres_start_angle(double &angle1, double &angle2)
DiagnosedPublisherT publisher_
A structure that holds the constructor parameters for the FrequencyStatus class.
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10