zoneset_msg_builder.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_ZONESET_MSG_BUILDER_H
17 #define PSEN_SCAN_V2_ZONESET_MSG_BUILDER_H
18 
19 #include <cstdint>
20 #include <string>
21 
22 #include <ros/time.h>
23 #include <geometry_msgs/Polygon.h>
24 
25 #include "psen_scan_v2/ZoneSet.h"
26 
27 namespace psen_scan_v2
28 {
30 {
31 public:
32  ZoneSet build() const;
33 
34 public:
35  ZoneSetMsgBuilder& headerSeq(uint32_t header_seq);
36  ZoneSetMsgBuilder& headerStamp(const ros::Time& header_stamp);
37  ZoneSetMsgBuilder& headerFrameId(const std::string& header_frame_id);
38  ZoneSetMsgBuilder& safety1(const geometry_msgs::Polygon& safety1);
39  ZoneSetMsgBuilder& safety2(const geometry_msgs::Polygon& safety2);
40  ZoneSetMsgBuilder& safety3(const geometry_msgs::Polygon& safety3);
41  ZoneSetMsgBuilder& warn1(const geometry_msgs::Polygon& warn1);
42  ZoneSetMsgBuilder& warn2(const geometry_msgs::Polygon& warn2);
43  ZoneSetMsgBuilder& muting1(const geometry_msgs::Polygon& muting1);
44  ZoneSetMsgBuilder& muting2(const geometry_msgs::Polygon& muting2);
45  ZoneSetMsgBuilder& speedLower(const float& speed_lower);
46  ZoneSetMsgBuilder& speedUpper(const float& speed_upper);
47 
48 private:
49  ZoneSet zoneset_msg_;
50 };
51 
52 inline ZoneSet ZoneSetMsgBuilder::build() const
53 {
54  return zoneset_msg_;
55 }
56 
58 {
59  zoneset_msg_.header.seq = seq;
60  return *this;
61 }
62 
64 {
65  zoneset_msg_.header.stamp = stamp;
66  return *this;
67 }
68 
69 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::headerFrameId(const std::string& frame_id)
70 {
71  zoneset_msg_.header.frame_id = frame_id;
72  return *this;
73 }
74 
75 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::safety1(const geometry_msgs::Polygon& safety1)
76 {
77  zoneset_msg_.safety1 = safety1;
78  return *this;
79 }
80 
81 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::safety2(const geometry_msgs::Polygon& safety2)
82 {
83  zoneset_msg_.safety2 = safety2;
84  return *this;
85 }
86 
87 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::safety3(const geometry_msgs::Polygon& safety3)
88 {
89  zoneset_msg_.safety3 = safety3;
90  return *this;
91 }
92 
93 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::warn1(const geometry_msgs::Polygon& warn1)
94 {
95  zoneset_msg_.warn1 = warn1;
96  return *this;
97 }
98 
99 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::warn2(const geometry_msgs::Polygon& warn2)
100 {
101  zoneset_msg_.warn2 = warn2;
102  return *this;
103 }
104 
105 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::muting1(const geometry_msgs::Polygon& muting1)
106 {
107  zoneset_msg_.muting1 = muting1;
108  return *this;
109 }
110 
111 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::muting2(const geometry_msgs::Polygon& muting2)
112 {
113  zoneset_msg_.muting2 = muting2;
114  return *this;
115 }
116 
117 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::speedLower(const float& speed_lower)
118 {
119  zoneset_msg_.speed_lower = speed_lower;
120  return *this;
121 }
122 
123 inline ZoneSetMsgBuilder& ZoneSetMsgBuilder::speedUpper(const float& speed_upper)
124 {
125  zoneset_msg_.speed_upper = speed_upper;
126  return *this;
127 }
128 
129 } // namespace psen_scan_v2
130 
131 #endif // PSEN_SCAN_V2_ZONESET_MSG_BUILDER_H
ZoneSetMsgBuilder & headerFrameId(const std::string &header_frame_id)
ZoneSetMsgBuilder & muting2(const geometry_msgs::Polygon &muting2)
ZoneSetMsgBuilder & safety2(const geometry_msgs::Polygon &safety2)
ZoneSetMsgBuilder & headerStamp(const ros::Time &header_stamp)
ZoneSetMsgBuilder & speedUpper(const float &speed_upper)
ZoneSetMsgBuilder & safety1(const geometry_msgs::Polygon &safety1)
ZoneSetMsgBuilder & speedLower(const float &speed_lower)
ZoneSetMsgBuilder & muting1(const geometry_msgs::Polygon &muting1)
ZoneSetMsgBuilder & warn2(const geometry_msgs::Polygon &warn2)
Root namespace for the ROS part.
ZoneSetMsgBuilder & safety3(const geometry_msgs::Polygon &safety3)
ZoneSetMsgBuilder & warn1(const geometry_msgs::Polygon &warn1)
ZoneSetMsgBuilder & headerSeq(uint32_t header_seq)


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Nov 5 2022 02:13:36