Class SickScanMarker
Defined in File sick_scan_marker.h
Nested Relationships
Nested Types
Class Documentation
-
class SickScanMarker
Public Functions
-
SickScanMarker(rosNodePtr nh = 0, const std::string &marker_topic = "", const std::string &marker_frame_id = "")
-
virtual ~SickScanMarker()
-
void updateMarker(const std::vector<SickScanMonField> &fields, int fieldset, int eval_field_logic)
-
void updateMarker(sick_scan_msg::LIDinputstateMsg &msg, int eval_field_logic)
-
void updateMarker(sick_scan_msg::LIDoutputstateMsg &msg, int eval_field_logic)
-
void updateMarker(sick_scan_msg::LFErecMsg &msg, int eval_field_logic)
Protected Functions
-
void publishMarker(void)
-
std::vector<ros_visualization_msgs::Marker> createMonFieldMarker(const std::vector<FieldInfo> &field_info)
-
std::vector<ros_visualization_msgs::Marker> createMonFieldLegend(const std::vector<FieldInfo> &field_info)
-
std::vector<ros_visualization_msgs::Marker> createMonFieldsetLegend(int fieldset)
-
std::vector<ros_visualization_msgs::Marker> createOutputStateLegend(const std::vector<std::string> &output_state, const std::vector<std::string> &output_count, const std::vector<ros_std_msgs::ColorRGBA> &output_colors)
Protected Attributes
-
rosNodePtr m_nh
-
std::string m_frame_id
-
rosPublisher<ros_visualization_msgs::MarkerArray> m_marker_publisher
-
int m_scan_mon_fieldset
-
std::vector<sick_scan_xd::SickScanMonField> m_scan_mon_fields
-
std::vector<ros_visualization_msgs::Marker> m_scan_mon_field_marker
-
std::vector<ros_visualization_msgs::Marker> m_scan_mon_field_legend
-
std::vector<ros_visualization_msgs::Marker> m_scan_fieldset_legend
-
std::vector<ros_visualization_msgs::Marker> m_scan_outputstate_legend
-
double m_marker_output_legend_offset_x
-
sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy
-
SickScanMarker(rosNodePtr nh = 0, const std::string &marker_topic = "", const std::string &marker_frame_id = "")