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_ |
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.
psen_scan_v2::ActiveZonesetNode::ActiveZonesetNode | ( | ros::NodeHandle & | nh | ) |
Constructor.
nh | Node handle for the ROS node on which the scanner topic is advertised. |
Definition at line 33 of file active_zoneset_node.cpp.
|
private |
Definition at line 78 of file active_zoneset_node.cpp.
void psen_scan_v2::ActiveZonesetNode::activeZonesetCallback | ( | const std_msgs::UInt8 & | zoneset_config | ) |
Definition at line 47 of file active_zoneset_node.cpp.
|
private |
Definition at line 98 of file active_zoneset_node.cpp.
|
private |
Definition at line 90 of file active_zoneset_node.cpp.
|
private |
deprecated: use ZoneSet activeZoneset() const instead
Definition at line 84 of file active_zoneset_node.cpp.
|
private |
Definition at line 73 of file active_zoneset_node.cpp.
|
private |
Definition at line 115 of file active_zoneset_node.cpp.
|
private |
Definition at line 53 of file active_zoneset_node.cpp.
void psen_scan_v2::ActiveZonesetNode::zonesetCallback | ( | const ZoneSetConfiguration & | zoneset_config | ) |
Definition at line 41 of file active_zoneset_node.cpp.
|
private |
Definition at line 76 of file active_zoneset_node.h.
|
private |
Definition at line 72 of file active_zoneset_node.h.
|
private |
Definition at line 78 of file active_zoneset_node.h.
|
private |
Definition at line 77 of file active_zoneset_node.h.
|
private |
Definition at line 70 of file active_zoneset_node.h.
|
private |
Definition at line 75 of file active_zoneset_node.h.
|
private |
Definition at line 73 of file active_zoneset_node.h.
|
private |
Definition at line 71 of file active_zoneset_node.h.