Public Member Functions | Private Member Functions | Private Attributes | List of all members
psen_scan_v2::ActiveZonesetNode Class Reference

ROS Node that continuously publishes a marker for the active_zoneset. More...

#include <active_zoneset_node.h>

Public Member Functions

void activeZonesetCallback (const std_msgs::UInt8 &zoneset_config)
 
 ActiveZonesetNode (ros::NodeHandle &nh)
 Constructor. More...
 
void zonesetCallback (const ZoneSetConfiguration &zoneset_config)
 

Private Member Functions

ZoneSet activeZoneset () const
 
void addDeleteMessageForUnusedLastMarkers ()
 
void addMarkers (std::vector< visualization_msgs::Marker > &new_markers)
 
ZoneSet getActiveZoneset () const
 
bool isAllInformationAvailable () const
 
void publishCurrentMarkers ()
 
void updateMarkers ()
 

Private Attributes

boost::optional< std_msgs::UInt8 > active_zoneset_id_
 
ros::Subscriber active_zoneset_subscriber_
 
std::vector< visualization_msgs::Marker > current_markers_
 
std::vector< visualization_msgs::Marker > last_markers_
 
ros::NodeHandle nh_
 
boost::optional< ZoneSetConfiguration > zoneset_config_
 
ros::Publisher zoneset_markers_
 
ros::Subscriber zoneset_subscriber_
 

Detailed Description

ROS Node that continuously publishes a marker for the active_zoneset.

subscribes to: ns/active_zoneset subscribes to: ns/zoneconfiguration

advertises: ns/active_zoneset_markers

Definition at line 43 of file active_zoneset_node.h.

Constructor & Destructor Documentation

◆ ActiveZonesetNode()

psen_scan_v2::ActiveZonesetNode::ActiveZonesetNode ( ros::NodeHandle nh)

Constructor.

Parameters
nhNode handle for the ROS node on which the scanner topic is advertised.

Definition at line 33 of file active_zoneset_node.cpp.

Member Function Documentation

◆ activeZoneset()

ZoneSet psen_scan_v2::ActiveZonesetNode::activeZoneset ( ) const
private

Definition at line 78 of file active_zoneset_node.cpp.

◆ activeZonesetCallback()

void psen_scan_v2::ActiveZonesetNode::activeZonesetCallback ( const std_msgs::UInt8 &  zoneset_config)

Definition at line 47 of file active_zoneset_node.cpp.

◆ addDeleteMessageForUnusedLastMarkers()

void psen_scan_v2::ActiveZonesetNode::addDeleteMessageForUnusedLastMarkers ( )
private

Definition at line 98 of file active_zoneset_node.cpp.

◆ addMarkers()

void psen_scan_v2::ActiveZonesetNode::addMarkers ( std::vector< visualization_msgs::Marker > &  new_markers)
private

Definition at line 90 of file active_zoneset_node.cpp.

◆ getActiveZoneset()

ZoneSet psen_scan_v2::ActiveZonesetNode::getActiveZoneset ( ) const
private

deprecated: use ZoneSet activeZoneset() const instead

Definition at line 84 of file active_zoneset_node.cpp.

◆ isAllInformationAvailable()

bool psen_scan_v2::ActiveZonesetNode::isAllInformationAvailable ( ) const
private

Definition at line 73 of file active_zoneset_node.cpp.

◆ publishCurrentMarkers()

void psen_scan_v2::ActiveZonesetNode::publishCurrentMarkers ( )
private

Definition at line 115 of file active_zoneset_node.cpp.

◆ updateMarkers()

void psen_scan_v2::ActiveZonesetNode::updateMarkers ( )
private

Definition at line 53 of file active_zoneset_node.cpp.

◆ zonesetCallback()

void psen_scan_v2::ActiveZonesetNode::zonesetCallback ( const ZoneSetConfiguration &  zoneset_config)

Definition at line 41 of file active_zoneset_node.cpp.

Member Data Documentation

◆ active_zoneset_id_

boost::optional<std_msgs::UInt8> psen_scan_v2::ActiveZonesetNode::active_zoneset_id_
private

Definition at line 76 of file active_zoneset_node.h.

◆ active_zoneset_subscriber_

ros::Subscriber psen_scan_v2::ActiveZonesetNode::active_zoneset_subscriber_
private

Definition at line 72 of file active_zoneset_node.h.

◆ current_markers_

std::vector<visualization_msgs::Marker> psen_scan_v2::ActiveZonesetNode::current_markers_
private

Definition at line 78 of file active_zoneset_node.h.

◆ last_markers_

std::vector<visualization_msgs::Marker> psen_scan_v2::ActiveZonesetNode::last_markers_
private

Definition at line 77 of file active_zoneset_node.h.

◆ nh_

ros::NodeHandle psen_scan_v2::ActiveZonesetNode::nh_
private

Definition at line 70 of file active_zoneset_node.h.

◆ zoneset_config_

boost::optional<ZoneSetConfiguration> psen_scan_v2::ActiveZonesetNode::zoneset_config_
private

Definition at line 75 of file active_zoneset_node.h.

◆ zoneset_markers_

ros::Publisher psen_scan_v2::ActiveZonesetNode::zoneset_markers_
private

Definition at line 73 of file active_zoneset_node.h.

◆ zoneset_subscriber_

ros::Subscriber psen_scan_v2::ActiveZonesetNode::zoneset_subscriber_
private

Definition at line 71 of file active_zoneset_node.h.


The documentation for this class was generated from the following files:


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Nov 25 2023 03:46:26