Go to the documentation of this file.00001
00012 #ifndef RAIL_SEGMENTATION_SEGMENTATION_ZONE_H_
00013 #define RAIL_SEGMENTATION_SEGMENTATION_ZONE_H_
00014
00015
00016 #include <string>
00017
00018 namespace rail
00019 {
00020 namespace segmentation
00021 {
00022
00030 class SegmentationZone
00031 {
00032 public:
00045 SegmentationZone(const std::string &name = "", const std::string &parent_frame_id = "",
00046 const std::string &child_frame_id = "", const std::string &bounding_frame_id = "",
00047 const std::string &segmentation_frame_id = "");
00048
00056 void setRemoveSurface(const bool remove_surface);
00057
00065 bool getRemoveSurface() const;
00066
00074 void setName(const std::string &name);
00075
00083 const std::string &getName() const;
00084
00092 void setParentFrameID(const std::string &parent_frame_id);
00093
00101 const std::string &getParentFrameID() const;
00102
00110 void setChildFrameID(const std::string &child_frame_id);
00111
00119 const std::string &getChildFrameID() const;
00120
00128 void setSegmentationFrameID(const std::string &segmentation_frame_id);
00129
00137 const std::string &getSegmentationFrameID() const;
00138
00146 void setBoundingFrameID(const std::string &bounding_frame_id);
00147
00155 const std::string &getBoundingFrameID() const;
00156
00164 void setRollMin(const double roll_min);
00165
00173 double getRollMin() const;
00174
00182 void setRollMax(const double roll_max);
00183
00191 double getRollMax() const;
00192
00200 void setPitchMin(const double pitch_min);
00201
00209 double getPitchMin() const;
00210
00218 void setPitchMax(const double pitch_max);
00219
00227 double getPitchMax() const;
00228
00236 void setYawMin(const double yaw_min);
00237
00245 double getYawMin() const;
00246
00254 void setYawMax(const double yaw_max);
00255
00263 double getYawMax() const;
00264
00272 void setXMin(const double x_min);
00273
00281 double getXMin() const;
00282
00290 void setXMax(const double x_max);
00291
00299 double getXMax() const;
00300
00308 void setYMin(const double y_min);
00309
00317 double getYMin() const;
00318
00326 void setYMax(const double y_max);
00327
00335 double getYMax() const;
00336
00344 void setZMin(const double z_min);
00345
00353 double getZMin() const;
00354
00362 void setZMax(const double z_max);
00363
00371 double getZMax() const;
00372
00373 private:
00375 bool remove_surface_;
00377 std::string name_, parent_frame_id_, child_frame_id_, segmentation_frame_id_, bounding_frame_id_;
00379 double roll_min_, roll_max_, pitch_min_, pitch_max_, yaw_min_, yaw_max_, x_min_, x_max_, y_min_, y_max_, z_min_,
00380 z_max_;
00381 };
00382
00383 }
00384 }
00385
00386 #endif