active_zoneset_node.h
Go to the documentation of this file.
1 // Copyright (c) 2021 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #ifndef PSEN_SCAN_V2_ACTIVE_ZONESET_NODE_H
17 #define PSEN_SCAN_V2_ACTIVE_ZONESET_NODE_H
18 
19 #include <string>
20 #include <vector>
21 #include <boost/optional.hpp>
22 
23 #include <ros/ros.h>
24 #include <visualization_msgs/Marker.h>
25 #include <std_msgs/UInt8.h>
26 
27 #include "psen_scan_v2/ZoneSetConfiguration.h"
28 
29 namespace psen_scan_v2
30 {
31 static const std::string DEFAULT_ACTIVE_ZONESET_TOPIC = "active_zoneset";
32 static const std::string DEFAULT_ZONECONFIGURATION_TOPIC = "zoneconfiguration";
33 static const std::string DEFAULT_ZONESET_MARKER_ARRAY_TOPIC = "active_zoneset_markers";
34 
44 {
45 public:
52 
53 public:
54  void zonesetCallback(const ZoneSetConfiguration& zoneset_config);
55  void activeZonesetCallback(const std_msgs::UInt8& zoneset_config);
56 
57 private:
58  void updateMarkers();
59  bool isAllInformationAvailable() const;
60 
62  [[deprecated("use ZoneSet activeZoneset() const instead")]] ZoneSet getActiveZoneset() const;
63  ZoneSet activeZoneset() const;
64 
65  void addMarkers(std::vector<visualization_msgs::Marker>& new_markers);
66  void publishCurrentMarkers();
68 
69 private:
74 
75  boost::optional<ZoneSetConfiguration> zoneset_config_;
76  boost::optional<std_msgs::UInt8> active_zoneset_id_;
77  std::vector<visualization_msgs::Marker> last_markers_;
78  std::vector<visualization_msgs::Marker> current_markers_;
79 };
80 
81 } // namespace psen_scan_v2
82 
83 #endif // PSEN_SCAN_V2_ACTIVE_ZONESET_NODE_H
psen_scan_v2::ActiveZonesetNode::addDeleteMessageForUnusedLastMarkers
void addDeleteMessageForUnusedLastMarkers()
Definition: active_zoneset_node.cpp:98
psen_scan_v2::ActiveZonesetNode::updateMarkers
void updateMarkers()
Definition: active_zoneset_node.cpp:53
ros::Publisher
psen_scan_v2::ActiveZonesetNode::publishCurrentMarkers
void publishCurrentMarkers()
Definition: active_zoneset_node.cpp:115
psen_scan_v2::ActiveZonesetNode::zonesetCallback
void zonesetCallback(const ZoneSetConfiguration &zoneset_config)
Definition: active_zoneset_node.cpp:41
psen_scan_v2::DEFAULT_ZONECONFIGURATION_TOPIC
static const std::string DEFAULT_ZONECONFIGURATION_TOPIC
Definition: active_zoneset_node.h:32
psen_scan_v2::ActiveZonesetNode::active_zoneset_subscriber_
ros::Subscriber active_zoneset_subscriber_
Definition: active_zoneset_node.h:72
psen_scan_v2::DEFAULT_ACTIVE_ZONESET_TOPIC
static const std::string DEFAULT_ACTIVE_ZONESET_TOPIC
Definition: active_zoneset_node.h:31
ros.h
psen_scan_v2::ActiveZonesetNode::addMarkers
void addMarkers(std::vector< visualization_msgs::Marker > &new_markers)
Definition: active_zoneset_node.cpp:90
psen_scan_v2::ActiveZonesetNode::isAllInformationAvailable
bool isAllInformationAvailable() const
Definition: active_zoneset_node.cpp:73
psen_scan_v2::ActiveZonesetNode
ROS Node that continuously publishes a marker for the active_zoneset.
Definition: active_zoneset_node.h:43
psen_scan_v2::ActiveZonesetNode::activeZoneset
ZoneSet activeZoneset() const
Definition: active_zoneset_node.cpp:78
psen_scan_v2::ActiveZonesetNode::zoneset_config_
boost::optional< ZoneSetConfiguration > zoneset_config_
Definition: active_zoneset_node.h:75
psen_scan_v2::ActiveZonesetNode::activeZonesetCallback
void activeZonesetCallback(const std_msgs::UInt8 &zoneset_config)
Definition: active_zoneset_node.cpp:47
psen_scan_v2::ActiveZonesetNode::getActiveZoneset
ZoneSet getActiveZoneset() const
Definition: active_zoneset_node.cpp:84
psen_scan_v2
Root namespace for the ROS part.
Definition: active_zoneset_node.h:29
psen_scan_v2::ActiveZonesetNode::zoneset_markers_
ros::Publisher zoneset_markers_
Definition: active_zoneset_node.h:73
psen_scan_v2::ActiveZonesetNode::active_zoneset_id_
boost::optional< std_msgs::UInt8 > active_zoneset_id_
Definition: active_zoneset_node.h:76
psen_scan_v2::ActiveZonesetNode::zoneset_subscriber_
ros::Subscriber zoneset_subscriber_
Definition: active_zoneset_node.h:71
psen_scan_v2::DEFAULT_ZONESET_MARKER_ARRAY_TOPIC
static const std::string DEFAULT_ZONESET_MARKER_ARRAY_TOPIC
Definition: active_zoneset_node.h:33
psen_scan_v2::ActiveZonesetNode::nh_
ros::NodeHandle nh_
Definition: active_zoneset_node.h:70
psen_scan_v2::ActiveZonesetNode::current_markers_
std::vector< visualization_msgs::Marker > current_markers_
Definition: active_zoneset_node.h:78
psen_scan_v2::ActiveZonesetNode::ActiveZonesetNode
ActiveZonesetNode(ros::NodeHandle &nh)
Constructor.
Definition: active_zoneset_node.cpp:33
psen_scan_v2::ActiveZonesetNode::last_markers_
std::vector< visualization_msgs::Marker > last_markers_
Definition: active_zoneset_node.h:77
ros::NodeHandle
ros::Subscriber


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