Visual Servoing Platform  version 3.5.1 under development (2023-09-22)
vpFeatureSegment.h
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Segment visual feature.
33  *
34  * Authors:
35  * Filip Novotny
36  *
37 *****************************************************************************/
38 
39 #ifndef vpFeatureSegment_H
40 #define vpFeatureSegment_H
41 
47 #include <visp3/core/vpMatrix.h>
48 #include <visp3/core/vpPoint.h>
49 #include <visp3/core/vpRGBa.h>
50 #include <visp3/visual_features/vpBasicFeature.h>
51 #include <visp3/visual_features/vpFeatureException.h>
52 
72 class VISP_EXPORT vpFeatureSegment : public vpBasicFeature
73 {
74 public:
75  // empty constructor
76  explicit vpFeatureSegment(bool normalized = false);
77 
79  virtual ~vpFeatureSegment() {}
80  // change values of the segment
81  void buildFrom(double x1, double y1, double Z1, double x2, double y2, double Z2);
82 
83  void display(const vpCameraParameters &cam, const vpImage<unsigned char> &I, const vpColor &color = vpColor::green,
84  unsigned int thickness = 1) const;
85  void display(const vpCameraParameters &cam, const vpImage<vpRGBa> &I, const vpColor &color = vpColor::green,
86  unsigned int thickness = 1) const;
88  vpFeatureSegment *duplicate() const;
89  // compute the error between two visual features from a subset
90  // a the possible features
91  vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL);
92 
99  inline double getXc() const { return s[0]; }
100 
107  inline double getYc() const { return s[1]; }
108 
116  inline double getL() const { return s[2]; }
117 
124  inline double getAlpha() const { return s[3]; }
125 
132  inline double getZ1() const { return Z1_; }
133 
141  inline double getZ2() const { return Z2_; }
142 
143  // Basic construction.
144  void init();
145 
146  // compute the interaction matrix from a subset a the possible features
147  vpMatrix interaction(unsigned int select = FEATURE_ALL);
148 
149  void print(unsigned int select = FEATURE_ALL) const;
150 
154  bool isNormalized() { return normalized_; };
155 
156  static unsigned int selectXc();
157  static unsigned int selectYc();
158  static unsigned int selectL();
159  static unsigned int selectAlpha();
160 
167  void setNormalized(bool normalized) { normalized_ = normalized; };
177  inline void setXc(double val)
178  {
179  s[0] = xc_ = val;
180  flags[0] = true;
181  }
191  inline void setYc(double val)
192  {
193  s[1] = yc_ = val;
194  flags[1] = true;
195  }
204  inline void setL(double val)
205  {
206  s[2] = l_ = val;
207  flags[2] = true;
208  }
217  inline void setAlpha(double val)
218  {
219  s[3] = alpha_ = val;
220  cos_a_ = cos(val);
221  sin_a_ = sin(val);
222  flags[3] = true;
223  }
224 
237  inline void setZ1(double val)
238  {
239  Z1_ = val;
240 
241  if (Z1_ < 0) {
242  vpERROR_TRACE("Point is behind the camera ");
243  std::cout << "Z1 = " << Z1_ << std::endl;
244 
245  throw(vpFeatureException(vpFeatureException::badInitializationError, "Point Z1 is behind the camera "));
246  }
247 
248  if (fabs(Z1_) < 1e-6) {
249  vpERROR_TRACE("Point Z1 coordinates is null ");
250  std::cout << "Z1 = " << Z1_ << std::endl;
251 
252  throw(vpFeatureException(vpFeatureException::badInitializationError, "Point Z1 coordinates is null"));
253  }
254 
255  flags[4] = true;
256  }
257 
270  inline void setZ2(double val)
271  {
272  Z2_ = val;
273 
274  if (Z2_ < 0) {
275  vpERROR_TRACE("Point Z2 is behind the camera ");
276  std::cout << "Z2 = " << Z2_ << std::endl;
277 
278  throw(vpFeatureException(vpFeatureException::badInitializationError, "Point Z2 is behind the camera "));
279  }
280 
281  if (fabs(Z2_) < 1e-6) {
282  vpERROR_TRACE("Point Z2 coordinates is null ");
283  std::cout << "Z2 = " << Z2_ << std::endl;
284 
285  throw(vpFeatureException(vpFeatureException::badInitializationError, "Point Z2 coordinates is null"));
286  }
287 
288  flags[5] = true;
289  }
290 
291 private:
292  double xc_;
293  double yc_;
294  double l_;
295  double alpha_;
296  double Z1_;
297  double Z2_;
298  double cos_a_;
299  double sin_a_;
300  bool normalized_;
301 };
302 
303 #endif
class that defines what is a visual feature
virtual vpColVector error(const vpBasicFeature &s_star, unsigned int select=FEATURE_ALL)
virtual void init()=0
virtual vpMatrix interaction(unsigned int select=FEATURE_ALL)=0
Compute the interaction matrix from a subset of the possible features.
virtual void print(unsigned int select=FEATURE_ALL) const =0
Print the name of the feature.
virtual void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpColor &color=vpColor::green, unsigned int thickness=1) const =0
virtual vpBasicFeature * duplicate() const =0
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:167
Class to define RGB colors available for display functionalities.
Definition: vpColor.h:152
static const vpColor green
Definition: vpColor.h:214
Error that can be emitted by the vpBasicFeature class and its derivates.
@ badInitializationError
Wrong feature initialization.
Class that defines a 2D segment visual features. This class allow to consider two sets of visual feat...
double getZ2() const
virtual ~vpFeatureSegment()
Destructor. Does nothing.
double getZ1() const
double getAlpha() const
void setAlpha(double val)
void setNormalized(bool normalized)
void setL(double val)
void setZ2(double val)
double getXc() const
void setZ1(double val)
double getYc() const
double getL() const
void setXc(double val)
void setYc(double val)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:152
#define vpERROR_TRACE
Definition: vpDebug.h:388