diff --git a/Doxyfile b/Doxyfile index e07c809..72ad05e 100644 --- a/Doxyfile +++ b/Doxyfile @@ -829,7 +829,7 @@ WARN_LOGFILE = # spaces. See also FILE_PATTERNS and EXTENSION_MAPPING # Note: If this tag is empty the current directory is searched. -INPUT = "./master_layer" +INPUT = # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses diff --git a/docs/html/MS5837_8h_source.html b/docs/html/MS5837_8h_source.html new file mode 100644 index 0000000..0efd574 --- /dev/null +++ b/docs/html/MS5837_8h_source.html @@ -0,0 +1,171 @@ + + + + + + + +Anahita: hardware_layer/hardware_arduino/include/MS5837.h Source File + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
MS5837.h
+
+
+
1 /* Blue Robotics Arduino MS5837-30BA Pressure/Temperature Sensor Library
+
2 ------------------------------------------------------------
+
3 
+
4 Title: Blue Robotics Arduino MS5837-30BA Pressure/Temperature Sensor Library
+
5 
+
6 Description: This library provides utilities to communicate with and to
+
7 read data from the Measurement Specialties MS5837-30BA pressure/temperature
+
8 sensor.
+
9 
+
10 Authors: Rustom Jehangir, Blue Robotics Inc.
+
11  Adam Å imko, Blue Robotics Inc.
+
12 
+
13 -------------------------------
+
14 The MIT License (MIT)
+
15 
+
16 Copyright (c) 2015 Blue Robotics Inc.
+
17 
+
18 Permission is hereby granted, free of charge, to any person obtaining a copy
+
19 of this software and associated documentation files (the "Software"), to deal
+
20 in the Software without restriction, including without limitation the rights
+
21 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+
22 copies of the Software, and to permit persons to whom the Software is
+
23 furnished to do so, subject to the following conditions:
+
24 
+
25 The above copyright notice and this permission notice shall be included in
+
26 all copies or substantial portions of the Software.
+
27 
+
28 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+
29 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+
30 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+
31 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+
32 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+
33 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+
34 THE SOFTWARE.
+
35 -------------------------------*/
+
36 
+
37 #ifndef MS5837_H_BLUEROBOTICS
+
38 #define MS5837_H_BLUEROBOTICS
+
39 
+
40 #include "Arduino.h"
+
41 
+
42 class MS5837 {
+
43 public:
+
44  static const float Pa;
+
45  static const float bar;
+
46  static const float mbar;
+
47 
+
48  static const uint8_t MS5837_30BA;
+
49  static const uint8_t MS5837_02BA;
+
50 
+
51  MS5837();
+
52 
+
53  bool init();
+
54 
+
58  void setModel(uint8_t model);
+
59 
+
63  void setFluidDensity(float density);
+
64 
+
67  void read();
+
68 
+
71  float pressure(float conversion = 1.0f);
+
72 
+
75  float temperature();
+
76 
+
80  float depth();
+
81 
+
84  float altitude();
+
85 
+
86 private:
+
87  uint16_t C[8];
+
88  uint32_t D1, D2;
+
89  int32_t TEMP;
+
90  int32_t P;
+
91  uint8_t _model;
+
92 
+
93  float fluidDensity;
+
94 
+
98  void calculate();
+
99 
+
100  uint8_t crc4(uint16_t n_prom[]);
+
101 };
+
102 
+
103 #endif
+
+
MS5837::altitude
float altitude()
Definition: MS5837.cpp:175
+
MS5837::setFluidDensity
void setFluidDensity(float density)
Definition: MS5837.cpp:56
+
MS5837::setModel
void setModel(uint8_t model)
Definition: MS5837.cpp:52
+
MS5837::temperature
float temperature()
Definition: MS5837.cpp:167
+
MS5837::pressure
float pressure(float conversion=1.0f)
Definition: MS5837.cpp:163
+
MS5837
Definition: MS5837.h:42
+
MS5837::depth
float depth()
Definition: MS5837.cpp:171
+
MS5837::read
void read()
Definition: MS5837.cpp:60
+ + + + diff --git a/docs/html/annotated.html b/docs/html/annotated.html index 25ace02..964c1f7 100644 --- a/docs/html/annotated.html +++ b/docs/html/annotated.html @@ -66,42 +66,214 @@
Here are the classes, structs, unions and interfaces with brief descriptions:
-
[detail level 123]
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +
[detail level 1234]
 Nmaster_layer
 Nanahita_thruster_manager
 CAnahitaThrusterManager
 Nstate_mach
 CBouyTask
 CFindBottomTarget
 CFindFrontTarget
 CGateTask
 CIdentifyTarget
 CLineTask
 CMarkerDropperTask
 CMoveToXYZ
 COctagonTask
 CRescueMode
 CStationKeeping
 CTaskBaseClass
 CTooFar
 CTorpedoTask
 CTransition
 Nstate_mach_gate_torpedo
 CBouyTask
 CFindBottomTarget
 CFindFrontTarget
 CGateTask
 CIdentifyTarget
 CLineTask
 CMarkerDropperTask
 CMoveToXYZ
 COctagonTask
 CRescueMode
 CStationKeeping
 CTaskBaseClass
 CTooFar
 CTorpedoTask
 CTransition
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
 NAccelerationControl
 Ncascaded_pid_dp_controller
 Ndisturbance_manager
 Nhardware_dvl
 Nimage_undistort
 Nmapping
 Nmaster_layer
 Nmtdef
 Nmtdevice
 Nmtnode
 Nnavigation
 NPID
 NPositionControl
 NPositionControlUnderactuated
 Nteledyne_navigator
 Ntest_trajectory_point
 Ntest_waypoint
 Ntest_waypoint_set
 Nthruster_allocator
 Ntrajectory_marker_publisher
 Nuuv_auv_actuator_interface
 Nuuv_control_interfaces
 Nuuv_thrusters
 Nuuv_trajectory_generator
 Nuuv_waypoints
 NVelocityControl
 Nvision_commons
 CBase_class
 CBuoy
 Ccolor_correctionClass defining generic interfaces and methods common for color correction methods
 CCrucifix
 CDVLData
 CDVLEthernet
 CDVLformat21_t
 CDVLHeader
 CDVLstatus
 CErrorDescriptor
 CGate
 CGrabber
 CLaplacianBlending
 CLine
 CMarker
 CMarkerDropper
 CMS5837
 Cname
 CObservation
 COctagon
 CPathMarker
 CPinger
 CStartGate
 CTestThis is a test class.

    +
  • +
+
 CTestGate
 CTorpedo
 CTriangularBuoy
diff --git a/docs/html/base__class_8h_source.html b/docs/html/base__class_8h_source.html new file mode 100644 index 0000000..83b98c0 --- /dev/null +++ b/docs/html/base__class_8h_source.html @@ -0,0 +1,202 @@ + + + + + + + +Anahita: vision_layer/vision_tasks/include/base_class.h Source File + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
base_class.h
+
+
+
1 #ifndef BASE_CLASS_H
+
2 #define BASE_CLASS_H
+
3 
+
4 #include <iostream>
+
5 #include <vector>
+
6 #include <mutex>
+
7 
+
8 #include "ros/ros.h"
+
9 #include "sensor_msgs/Image.h"
+
10 #include "opencv2/imgproc/imgproc.hpp"
+
11 #include "opencv2/core/core.hpp"
+
12 #include "opencv2/imgproc/imgproc_c.h"
+
13 #include "opencv2/highgui/highgui.hpp"
+
14 #include <cv_bridge/cv_bridge.h>
+
15 #include <image_transport/image_transport.h>
+
16 #include <dynamic_reconfigure/server.h>
+
17 #include <geometry_msgs/PointStamped.h>
+
18 #include <sensor_msgs/image_encodings.h>
+
19 #include <geometry_msgs/Pose2D.h>
+
20 #include <std_msgs/Float32.h>
+
21 #include <std_msgs/Bool.h>
+
22 #include <sensor_msgs/image_encodings.h>
+
23 #include <geometry_msgs/Point32.h>
+
24 #include <stdlib.h>
+
25 #include <string>
+
26 #include <boost/thread.hpp>
+
27 
+
28 #include <filter.h>
+
29 #include <contour.h>
+
30 #include <morph.h>
+
31 #include <threshold.h>
+
32 #include <geometry.h>
+
33 
+ +
35 {
+
36 
+
37 protected:
+
38  int front_low_g_;
+
39  int front_high_g_;
+
40  int front_low_r_;
+
41  int front_high_r_;
+
42  int front_low_b_;
+
43  int front_high_b_;
+
44  int front_opening_mat_point_;
+
45  int front_opening_iter_;
+
46  int front_closing_mat_point_;
+
47  int front_closing_iter_;
+
48  int front_bilateral_iter_;
+
49 
+
50  int bottom_low_g_;
+
51  int bottom_low_r_;
+
52  int bottom_low_b_;
+
53  int bottom_high_g_;
+
54  int bottom_high_r_;
+
55  int bottom_high_b_;
+
56  int bottom_closing_mat_point_;
+
57  int bottom_closing_iter_;
+
58  int bottom_opening_iter_;
+
59  int bottom_opening_mat_point_;
+
60  int bottom_bilateral_iter_;
+
61 
+
62  bool close_task = false;
+
63 
+
64  image_transport::Subscriber front_image_sub;
+
65  image_transport::Subscriber bottom_image_sub;
+
66 
+
67  image_transport::Subscriber enhanced_image_sub;
+
68 
+
69  image_transport::Publisher bottom_thresholded_pub;
+
70  image_transport::Publisher bottom_marked_pub;
+
71 
+
72  image_transport::Publisher front_thresholded_pub;
+
73  image_transport::Publisher front_marked_pub;
+
74  image_transport::Publisher front_edges_pub;
+
75 
+
76  ros::Publisher front_x_coordinate_pub;
+
77  ros::Publisher front_y_coordinate_pub;
+
78  ros::Publisher front_z_coordinate_pub;
+
79  ros::Publisher bottom_x_coordinate_pub;
+
80  ros::Publisher bottom_y_coordinate_pub;
+
81  ros::Publisher bottom_z_coordinate_pub;
+
82 
+
83  ros::Publisher detection_pub;
+
84 
+
85 public:
+
86  Base_class();
+
87  ros::NodeHandle nh;
+
88  image_transport::ImageTransport it;
+
89 
+
90  std_msgs::Float32 front_x_coordinate;
+
91  std_msgs::Float32 front_y_coordinate;
+
92  std_msgs::Float32 front_z_coordinate;
+
93 
+
94  std_msgs::Float32 bottom_x_coordinate;
+
95  std_msgs::Float32 bottom_y_coordinate;
+
96  std_msgs::Float32 bottom_z_coordinate;
+
97 
+
98  cv::Mat image_front;
+
99  cv::Mat image_bottom;
+
100  cv::Mat image_front_marked;
+
101  cv::Mat image_bottom_marked;
+
102  cv::Mat image_front_thresholded;
+
103  cv::Mat image_bottom_thresholded;
+
104  cv::Mat enhanced_image;
+
105 
+
106  virtual void spinThreadFront();
+
107  virtual void spinThreadBottom();
+
108  void bottomTaskHandling(bool status);
+
109  void frontTaskHandling(bool status);
+
110  void imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg);
+
111  void imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg);
+
112  void fusionCallback(const sensor_msgs::Image::ConstPtr &msg);
+
113  virtual void loadParams();
+
114  void init();
+
115 
+
116  boost::thread *spin_thread_bottom;
+
117  boost::thread *spin_thread_front;
+
118 
+
119  std::mutex vision_mutex;
+
120 };
+
121 #endif
+
+
Base_class
Definition: base_class.h:34
+ + + + diff --git a/docs/html/buoy_8h_source.html b/docs/html/buoy_8h_source.html new file mode 100644 index 0000000..035c213 --- /dev/null +++ b/docs/html/buoy_8h_source.html @@ -0,0 +1,119 @@ + + + + + + + +Anahita: vision_layer/vision_tasks/include/buoy.h Source File + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
buoy.h
+
+
+
1 #ifndef BUOY_TASK_H
+
2 #define BUOY_TASK_H
+
3 
+
4 #include "base_class.h"
+
5 #include <vision_tasks/buoyRangeConfig.h>
+
6 
+
7 class Buoy : public Base_class
+
8 {
+
9 protected:
+
10 
+
11  ros::NodeHandle nh;
+
12  image_transport::Publisher blue_filtered_pub;
+
13  image_transport::Subscriber image_raw_sub;
+
14 
+
15  std::string camera_frame_;
+
16  double clahe_clip_;
+
17  int clahe_grid_size_;
+
18  int clahe_bilateral_iter_;
+
19  int balanced_bilateral_iter_;
+
20  double denoise_h_;
+
21  int data_low_h[3] = {0, 12, 0};
+
22  int data_high_h[3] = {17, 40, 56};
+
23  int data_low_s[3] = {206, 183, 0};
+
24  int data_high_s[3] = {255, 255, 255};
+
25  int data_low_v[3] = {30, 3, 2};
+
26  int data_high_v[3] = {255, 255, 82};
+
27  void callback(vision_tasks::buoyRangeConfig &config, double level);
+
28  void imageCallback(const sensor_msgs::Image::ConstPtr &msg);
+
29 
+
30 public:
+
31  Buoy();
+
32  void switchColor(int);
+
33  void spinThreadFront();
+
34  void spinThread();
+
35  int current_color;
+
36 };
+
37 #endif // BUOY_TASK_H
+
+
Base_class
Definition: base_class.h:34
+
Buoy
Definition: buoy.h:7
+ + + + diff --git a/docs/html/camera__parameters_8h_source.html b/docs/html/camera__parameters_8h_source.html new file mode 100644 index 0000000..d520c1c --- /dev/null +++ b/docs/html/camera__parameters_8h_source.html @@ -0,0 +1,293 @@ + + + + + + + +Anahita: vision_layer/image_undistort/include/image_undistort/camera_parameters.h Source File + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
camera_parameters.h
+
+
+
1 #ifndef IMAGE_UNDISTORT_CAMERA_PARAMETERS_H
+
2 #define IMAGE_UNDISTORT_CAMERA_PARAMETERS_H
+
3 
+
4 #include <ros/ros.h>
+
5 #include <sensor_msgs/CameraInfo.h>
+
6 
+
7 #include <cv_bridge/cv_bridge.h>
+
8 
+
9 #include <Eigen/Dense>
+
10 
+
11 namespace image_undistort {
+
12 
+
13 enum class CameraSide { FIRST, SECOND };
+
14 enum class CameraIO { INPUT, OUTPUT };
+
15 enum class DistortionModel {
+
16  NONE,
+
17  RADTAN,
+
18  EQUIDISTANT,
+
19  FOV,
+
20  OMNI,
+
21  OMNIRADTAN,
+
22  DOUBLESPHERE,
+
23  UNIFIED,
+
24  EXTENDEDUNIFIED
+
25 };
+
26 enum class DistortionProcessing { UNDISTORT, PRESERVE };
+
27 
+
28 // holds basic properties of a camera
+ +
30  public:
+
31  BaseCameraParameters(const ros::NodeHandle& nh,
+
32  const std::string& camera_namespace,
+
33  const bool invert_T);
+
34 
+
35  BaseCameraParameters(const sensor_msgs::CameraInfo& camera_info);
+
36 
+
37  BaseCameraParameters(const cv::Size& resolution_in,
+
38  const Eigen::Matrix<double, 4, 4>& T_in,
+
39  const Eigen::Matrix<double, 3, 3>& K_in);
+
40 
+
41  const cv::Size& resolution() const; // get image size
+
42 
+
43  const Eigen::Matrix<double, 4, 4>& T() const; // get transformation matrix
+
44  const Eigen::Ref<const Eigen::Matrix<double, 3, 3>> R()
+
45  const; // get rotation matrix
+
46  const Eigen::Ref<const Eigen::Matrix<double, 3, 1>> p()
+
47  const; // get position vector
+
48 
+
49  const Eigen::Matrix<double, 3, 4>& P() const; // get projection matrix
+
50  const Eigen::Matrix<double, 3, 3>& K() const; // get camera matrix
+
51 
+
52  bool operator==(const BaseCameraParameters& B) const;
+
53  bool operator!=(const BaseCameraParameters& B) const;
+
54 
+
55  private:
+
56  template <typename Derived>
+
57  static void xmlRpcToMatrix(const XmlRpc::XmlRpcValue& const_input,
+
58  Eigen::MatrixBase<Derived>* output) {
+
59  // A local copy is required as the methods that allow you to access the
+
60  // XmlRpc values as doubles are not const and so cannot be used with the
+
61  // const ref
+
62  XmlRpc::XmlRpcValue input = const_input;
+
63 
+
64  if (input.size() != output->rows()) {
+
65  throw std::runtime_error("Loaded matrix has incorrect number of rows");
+
66  }
+
67  for (size_t i = 0; i < output->rows(); ++i) {
+
68  if (input[i].size() != output->cols()) {
+
69  throw std::runtime_error(
+
70  "Loaded matrix has incorrect number of columns");
+
71  }
+
72  for (size_t j = 0; j < output->cols(); ++j) {
+
73  output->coeffRef(i, j) = input[i][j];
+
74  }
+
75  }
+
76  }
+
77 
+
78  cv::Size resolution_;
+
79  Eigen::Matrix<double, 4, 4> T_;
+
80  Eigen::Matrix<double, 3, 4> P_;
+
81  Eigen::Matrix<double, 3, 3> K_;
+
82 };
+
83 
+
84 // basic camera properties + distortion parameters
+ +
86  public:
+
87  InputCameraParameters(const ros::NodeHandle& nh,
+
88  const std::string& camera_namespace,
+
89  const bool invert_T = false);
+
90 
+
91  InputCameraParameters(const sensor_msgs::CameraInfo& camera_info);
+
92 
+
93  InputCameraParameters(const cv::Size& resolution_in,
+
94  const Eigen::Matrix<double, 4, 4>& T_in,
+
95  const Eigen::Matrix<double, 3, 3>& K_in,
+
96  const std::vector<double>& D_in,
+
97  const DistortionModel& distortion_model);
+
98 
+
99  const std::vector<double>& D() const; // get distortion vector
+
100  const DistortionModel& distortionModel() const;
+
101 
+
102  bool operator==(const InputCameraParameters& B) const;
+
103  bool operator!=(const InputCameraParameters& B) const;
+
104 
+
105  private:
+
106  static const DistortionModel stringToDistortion(
+
107  const std::string& distortion_model, const std::string& camera_model);
+
108 
+
109  std::vector<double> D_;
+
110  DistortionModel distortion_model_;
+
111 };
+
112 
+
113 // basic camera properties + anything special to output cameras (currently
+
114 // nothing)
+ +
116  public:
+
117  using BaseCameraParameters::BaseCameraParameters;
+
118 };
+
119 
+
120 // holds the camera parameters of the input camera and virtual output camera
+ +
122  public:
+
123  CameraParametersPair(const DistortionProcessing distortion_processing =
+
124  DistortionProcessing::UNDISTORT);
+
125 
+
126  bool setCameraParameters(const ros::NodeHandle& nh,
+
127  const std::string& camera_namespace,
+
128  const CameraIO& io, const bool invert_T = false);
+
129 
+
130  bool setCameraParameters(const sensor_msgs::CameraInfo& camera_info,
+
131  const CameraIO& io);
+
132 
+
133  bool setInputCameraParameters(const cv::Size& resolution,
+
134  const Eigen::Matrix<double, 4, 4>& T,
+
135  const Eigen::Matrix<double, 3, 3>& K,
+
136  const std::vector<double>& D,
+
137  const DistortionModel& distortion_model);
+
138 
+
139  bool setOutputCameraParameters(const cv::Size& resolution,
+
140  const Eigen::Matrix<double, 4, 4>& T,
+
141  const Eigen::Matrix<double, 3, 3>& K);
+
142 
+
143  bool setOutputFromInput(const double scale);
+
144 
+
145  bool setOptimalOutputCameraParameters(const double scale);
+
146 
+
147  const DistortionProcessing& distortionProcessing() const;
+
148 
+
149  void generateCameraInfoMessage(const CameraIO& io,
+
150  sensor_msgs::CameraInfo* camera_info) const;
+
151 
+
152  const std::shared_ptr<InputCameraParameters>& getInputPtr() const;
+
153  const std::shared_ptr<OutputCameraParameters>& getOutputPtr() const;
+
154 
+
155  bool valid() const;
+
156  bool valid(const CameraIO& io) const;
+
157 
+
158  bool operator==(const CameraParametersPair& B) const;
+
159  bool operator!=(const CameraParametersPair& B) const;
+
160 
+
161  private:
+
162  std::shared_ptr<InputCameraParameters> input_ptr_;
+
163  std::shared_ptr<OutputCameraParameters> output_ptr_;
+
164 
+
165  DistortionProcessing distortion_processing_;
+
166 
+
167  static constexpr double kFocalLengthEstimationAttempts = 100;
+
168 };
+
169 
+
170 // holds the camera parameters of the first and second camera and uses them to
+
171 // generate virtual output cameras with properties that will produce correctly
+
172 // rectified images
+ +
174  public:
+
175  StereoCameraParameters(const double scale = 1.0);
+
176 
+
177  bool setInputCameraParameters(const ros::NodeHandle& nh,
+
178  const std::string& camera_namespace,
+
179  const CameraSide& side, const bool invert_T);
+
180 
+
181  bool setInputCameraParameters(const sensor_msgs::CameraInfo& camera_info,
+
182  const CameraSide& side);
+
183 
+
184  bool setInputCameraParameters(const cv::Size& resolution,
+
185  const Eigen::Matrix<double, 4, 4>& T,
+
186  const Eigen::Matrix<double, 3, 3>& K,
+
187  const std::vector<double>& D,
+
188  const DistortionModel& distortion_model,
+
189  const CameraSide& side);
+
190 
+
191  void generateCameraInfoMessage(const CameraSide& side, const CameraIO& io,
+
192  sensor_msgs::CameraInfo* camera_info) const;
+
193 
+
194  const CameraParametersPair& getFirst() const;
+
195  const CameraParametersPair& getSecond() const;
+
196 
+
197  bool valid() const;
+
198  bool valid(const CameraSide& side, const CameraIO& io) const;
+
199 
+
200  private:
+
201  bool generateRectificationParameters();
+
202 
+
203  double scale_;
+
204  CameraParametersPair first_;
+
205  CameraParametersPair second_;
+
206 };
+
207 } // namespace image_undistort
+
208 #endif // CAMERA_PARAMETERS_H
+
+
image_undistort::OutputCameraParameters
Definition: camera_parameters.h:115
+
image_undistort::InputCameraParameters
Definition: camera_parameters.h:85
+
image_undistort::BaseCameraParameters
Definition: camera_parameters.h:29
+
image_undistort::CameraParametersPair
Definition: camera_parameters.h:121
+
image_undistort::StereoCameraParameters
Definition: camera_parameters.h:173
+ + + + diff --git a/docs/html/classAccelerationControl_1_1AccelerationControllerNode-members.html b/docs/html/classAccelerationControl_1_1AccelerationControllerNode-members.html new file mode 100644 index 0000000..5d9c499 --- /dev/null +++ b/docs/html/classAccelerationControl_1_1AccelerationControllerNode-members.html @@ -0,0 +1,99 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
AccelerationControl.AccelerationControllerNode Member List
+
+
+ +

This is the complete list of members for AccelerationControl.AccelerationControllerNode, including all inherited members.

+ + + + + + + + + + + + + + + + + +
__init__(self) (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
acc_ (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
accel_callback(self, msg) (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
force_callback(self, msg) (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
inertial (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
inertial_tensor (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
mass (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
mass_inertial_matrix (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
pub_gen_force (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
ready (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
sub_accel (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
sub_force (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
sub_vel (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
vehicle_model (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
vel_ (defined in AccelerationControl.AccelerationControllerNode)AccelerationControl.AccelerationControllerNode
vel_callback(self, msg)AccelerationControl.AccelerationControllerNode
+ + + + diff --git a/docs/html/classAccelerationControl_1_1AccelerationControllerNode.html b/docs/html/classAccelerationControl_1_1AccelerationControllerNode.html new file mode 100644 index 0000000..6655e0d --- /dev/null +++ b/docs/html/classAccelerationControl_1_1AccelerationControllerNode.html @@ -0,0 +1,170 @@ + + + + + + + +Anahita: AccelerationControl.AccelerationControllerNode Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
AccelerationControl.AccelerationControllerNode Class Reference
+
+
+ + + + + + + + + + +

+Public Member Functions

+def __init__ (self)
 
+def force_callback (self, msg)
 
def vel_callback (self, msg)
 
+def accel_callback (self, msg)
 
+ + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Attributes

vehicle_model
 
ready
 
mass
 
inertial_tensor
 
mass_inertial_matrix
 
vel_
 
acc_
 
pub_gen_force
 
sub_accel
 
sub_vel
 
sub_force
 
inertial
 
+

Member Function Documentation

+ +

◆ vel_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def AccelerationControl.AccelerationControllerNode.vel_callback ( self,
 msg 
)
+
+
Handle updated measured velocity callback.
+
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classBase__class-members.html b/docs/html/classBase__class-members.html new file mode 100644 index 0000000..5d38297 --- /dev/null +++ b/docs/html/classBase__class-members.html @@ -0,0 +1,145 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Base_class Member List
+
+
+ +

This is the complete list of members for Base_class, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() (defined in Base_class)Base_classvirtual
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() (defined in Base_class)Base_classvirtual
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classBase__class.html b/docs/html/classBase__class.html new file mode 100644 index 0000000..8b76049 --- /dev/null +++ b/docs/html/classBase__class.html @@ -0,0 +1,312 @@ + + + + + + + +Anahita: Base_class Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +Public Attributes | +Protected Attributes | +List of all members
+
+
Base_class Class Reference
+
+
+
+Inheritance diagram for Base_class:
+
+
+ + +Buoy +Crucifix +Gate +Grabber +Line +Marker +MarkerDropper +Octagon +PathMarker +Pinger +StartGate +TestGate +Torpedo +TriangularBuoy + +
+ + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void spinThreadFront ()
 
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+virtual void loadParams ()
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Attributes

+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Protected Attributes

+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classBase__class.png b/docs/html/classBase__class.png new file mode 100644 index 0000000..cc933f5 Binary files /dev/null and b/docs/html/classBase__class.png differ diff --git a/docs/html/classBuoy-members.html b/docs/html/classBuoy-members.html new file mode 100644 index 0000000..d9e73cf --- /dev/null +++ b/docs/html/classBuoy-members.html @@ -0,0 +1,165 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Buoy Member List
+
+
+ +

This is the complete list of members for Buoy, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
balanced_bilateral_iter_ (defined in Buoy)Buoyprotected
Base_class() (defined in Base_class)Base_class
blue_filtered_pub (defined in Buoy)Buoyprotected
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
Buoy() (defined in Buoy)Buoy
callback(vision_tasks::buoyRangeConfig &config, double level) (defined in Buoy)Buoyprotected
camera_frame_ (defined in Buoy)Buoyprotected
clahe_bilateral_iter_ (defined in Buoy)Buoyprotected
clahe_clip_ (defined in Buoy)Buoyprotected
clahe_grid_size_ (defined in Buoy)Buoyprotected
close_task (defined in Base_class)Base_classprotected
current_color (defined in Buoy)Buoy
data_high_h (defined in Buoy)Buoyprotected
data_high_s (defined in Buoy)Buoyprotected
data_high_v (defined in Buoy)Buoyprotected
data_low_h (defined in Buoy)Buoyprotected
data_low_s (defined in Buoy)Buoyprotected
data_low_v (defined in Buoy)Buoyprotected
denoise_h_ (defined in Buoy)Buoyprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
image_raw_sub (defined in Buoy)Buoyprotected
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Buoy)Buoyprotected
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() (defined in Base_class)Base_classvirtual
nh (defined in Buoy)Buoyprotected
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThread() (defined in Buoy)Buoy
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() (defined in Buoy)Buoyvirtual
switchColor(int) (defined in Buoy)Buoy
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classBuoy.html b/docs/html/classBuoy.html new file mode 100644 index 0000000..4c4fe4e --- /dev/null +++ b/docs/html/classBuoy.html @@ -0,0 +1,366 @@ + + + + + + + +Anahita: Buoy Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +Public Attributes | +Protected Member Functions | +Protected Attributes | +List of all members
+
+
Buoy Class Reference
+
+
+
+Inheritance diagram for Buoy:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void switchColor (int)
 
+void spinThreadFront ()
 
+void spinThread ()
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+virtual void loadParams ()
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Attributes

+int current_color
 
- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
+ + + + + +

+Protected Member Functions

+void callback (vision_tasks::buoyRangeConfig &config, double level)
 
+void imageCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Protected Attributes

+ros::NodeHandle nh
 
+image_transport::Publisher blue_filtered_pub
 
+image_transport::Subscriber image_raw_sub
 
+std::string camera_frame_
 
+double clahe_clip_
 
+int clahe_grid_size_
 
+int clahe_bilateral_iter_
 
+int balanced_bilateral_iter_
 
+double denoise_h_
 
+int data_low_h [3] = {0, 12, 0}
 
+int data_high_h [3] = {17, 40, 56}
 
+int data_low_s [3] = {206, 183, 0}
 
+int data_high_s [3] = {255, 255, 255}
 
+int data_low_v [3] = {30, 3, 2}
 
+int data_high_v [3] = {255, 255, 82}
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classBuoy.png b/docs/html/classBuoy.png new file mode 100644 index 0000000..d2ea25d Binary files /dev/null and b/docs/html/classBuoy.png differ diff --git a/docs/html/classCrucifix-members.html b/docs/html/classCrucifix-members.html new file mode 100644 index 0000000..b36f512 --- /dev/null +++ b/docs/html/classCrucifix-members.html @@ -0,0 +1,147 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Crucifix Member List
+
+
+ +

This is the complete list of members for Crucifix, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
Crucifix() (defined in Crucifix)Crucifix
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in Crucifix)Crucifixvirtual
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() override (defined in Crucifix)Crucifixvirtual
spinThreadFront() override (defined in Crucifix)Crucifixvirtual
vision_mutex (defined in Base_class)Base_class
~Crucifix() (defined in Crucifix)Crucifix
+ + + + diff --git a/docs/html/classCrucifix.html b/docs/html/classCrucifix.html new file mode 100644 index 0000000..043b11f --- /dev/null +++ b/docs/html/classCrucifix.html @@ -0,0 +1,297 @@ + + + + + + + +Anahita: Crucifix Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
Crucifix Class Reference
+
+
+
+Inheritance diagram for Crucifix:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void loadParams () override
 
+virtual void spinThreadFront () override
 
+virtual void spinThreadBottom () override
 
- Public Member Functions inherited from Base_class
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classCrucifix.png b/docs/html/classCrucifix.png new file mode 100644 index 0000000..06444c8 Binary files /dev/null and b/docs/html/classCrucifix.png differ diff --git a/docs/html/classDVLEthernet-members.html b/docs/html/classDVLEthernet-members.html new file mode 100644 index 0000000..739de1d --- /dev/null +++ b/docs/html/classDVLEthernet-members.html @@ -0,0 +1,84 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
DVLEthernet Member List
+
+
+ +

This is the complete list of members for DVLEthernet, including all inherited members.

+ + + + + + +
Connect(std::string address, int port) (defined in DVLEthernet)DVLEthernet
DVLEthernet() (defined in DVLEthernet)DVLEthernet
GetRawData() (defined in DVLEthernet)DVLEthernet
Receive() (defined in DVLEthernet)DVLEthernet
~DVLEthernet() (defined in DVLEthernet)DVLEthernet
+ + + + diff --git a/docs/html/classDVLEthernet.html b/docs/html/classDVLEthernet.html new file mode 100644 index 0000000..cb81df3 --- /dev/null +++ b/docs/html/classDVLEthernet.html @@ -0,0 +1,96 @@ + + + + + + + +Anahita: DVLEthernet Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
DVLEthernet Class Reference
+
+
+ + + + + + + + +

+Public Member Functions

+void Connect (std::string address, int port)
 
+void Receive ()
 
+char * GetRawData ()
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classErrorDescriptor-members.html b/docs/html/classErrorDescriptor-members.html new file mode 100644 index 0000000..5c22ed5 --- /dev/null +++ b/docs/html/classErrorDescriptor-members.html @@ -0,0 +1,87 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
ErrorDescriptor Member List
+
+
+ +

This is the complete list of members for ErrorDescriptor, including all inherited members.

+ + + + + + + + + +
ErrorDescriptor(std::string _name) (defined in ErrorDescriptor)ErrorDescriptor
errorToPWM(double _current_value) (defined in ErrorDescriptor)ErrorDescriptor
getCurrentValue() (defined in ErrorDescriptor)ErrorDescriptor
getPWM() (defined in ErrorDescriptor)ErrorDescriptor
setPID(float new_p, float new_i, float new_d, float new_band) (defined in ErrorDescriptor)ErrorDescriptor
setReference(double _value) (defined in ErrorDescriptor)ErrorDescriptor
setType(std::string _name) (defined in ErrorDescriptor)ErrorDescriptor
~ErrorDescriptor() (defined in ErrorDescriptor)ErrorDescriptor
+ + + + diff --git a/docs/html/classErrorDescriptor.html b/docs/html/classErrorDescriptor.html new file mode 100644 index 0000000..6bbbcbd --- /dev/null +++ b/docs/html/classErrorDescriptor.html @@ -0,0 +1,108 @@ + + + + + + + +Anahita: ErrorDescriptor Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
ErrorDescriptor Class Reference
+
+
+ + + + + + + + + + + + + + + + +

+Public Member Functions

ErrorDescriptor (std::string _name)
 
+void setPID (float new_p, float new_i, float new_d, float new_band)
 
+void setType (std::string _name)
 
+void setReference (double _value)
 
+void errorToPWM (double _current_value)
 
+int getPWM ()
 
+double getCurrentValue ()
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classGate-members.html b/docs/html/classGate-members.html new file mode 100644 index 0000000..459990d --- /dev/null +++ b/docs/html/classGate-members.html @@ -0,0 +1,146 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Gate Member List
+
+
+ +

This is the complete list of members for Gate, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
Gate() (defined in Gate)Gate
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in Gate)Gatevirtual
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() override (defined in Gate)Gatevirtual
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classGate.html b/docs/html/classGate.html new file mode 100644 index 0000000..d2e8c4d --- /dev/null +++ b/docs/html/classGate.html @@ -0,0 +1,297 @@ + + + + + + + +Anahita: Gate Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
Gate Class Reference
+
+
+
+Inheritance diagram for Gate:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void loadParams () override
 
+void spinThreadFront () override
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classGate.png b/docs/html/classGate.png new file mode 100644 index 0000000..a53fb39 Binary files /dev/null and b/docs/html/classGate.png differ diff --git a/docs/html/classGrabber-members.html b/docs/html/classGrabber-members.html new file mode 100644 index 0000000..60151c9 --- /dev/null +++ b/docs/html/classGrabber-members.html @@ -0,0 +1,147 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Grabber Member List
+
+
+ +

This is the complete list of members for Grabber, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
Grabber() (defined in Grabber)Grabber
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in Grabber)Grabbervirtual
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() override (defined in Grabber)Grabbervirtual
spinThreadFront() override (defined in Grabber)Grabbervirtual
vision_mutex (defined in Base_class)Base_class
~Grabber() (defined in Grabber)Grabber
+ + + + diff --git a/docs/html/classGrabber.html b/docs/html/classGrabber.html new file mode 100644 index 0000000..804a5c3 --- /dev/null +++ b/docs/html/classGrabber.html @@ -0,0 +1,297 @@ + + + + + + + +Anahita: Grabber Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
Grabber Class Reference
+
+
+
+Inheritance diagram for Grabber:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void loadParams () override
 
+virtual void spinThreadFront () override
 
+virtual void spinThreadBottom () override
 
- Public Member Functions inherited from Base_class
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classGrabber.png b/docs/html/classGrabber.png new file mode 100644 index 0000000..8953504 Binary files /dev/null and b/docs/html/classGrabber.png differ diff --git a/docs/html/classLaplacianBlending-members.html b/docs/html/classLaplacianBlending-members.html new file mode 100644 index 0000000..b38b951 --- /dev/null +++ b/docs/html/classLaplacianBlending-members.html @@ -0,0 +1,81 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
LaplacianBlending Member List
+
+
+ +

This is the complete list of members for LaplacianBlending, including all inherited members.

+ + + +
blend() (defined in LaplacianBlending)LaplacianBlending
LaplacianBlending(const Mat_< Vec3f > &_left, const Mat_< Vec3f > &_right, const Mat_< float > &_leftMask, const Mat_< float > &_rightMask, int _levels) (defined in LaplacianBlending)LaplacianBlending
+ + + + diff --git a/docs/html/classLaplacianBlending.html b/docs/html/classLaplacianBlending.html new file mode 100644 index 0000000..ec22388 --- /dev/null +++ b/docs/html/classLaplacianBlending.html @@ -0,0 +1,93 @@ + + + + + + + +Anahita: LaplacianBlending Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
LaplacianBlending Class Reference
+
+
+ + + + + + +

+Public Member Functions

LaplacianBlending (const Mat_< Vec3f > &_left, const Mat_< Vec3f > &_right, const Mat_< float > &_leftMask, const Mat_< float > &_rightMask, int _levels)
 
+Mat_< Vec3f > blend ()
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classLine-members.html b/docs/html/classLine-members.html new file mode 100644 index 0000000..115ed7a --- /dev/null +++ b/docs/html/classLine-members.html @@ -0,0 +1,154 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Line Member List
+
+
+ +

This is the complete list of members for Line, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
ang_pub (defined in Line)Lineprotected
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
callback(vision_tasks::lineRangeConfig &config, double level) (defined in Line)Lineprotected
camera_frame_ (defined in Line)Lineprotected
close_task (defined in Base_class)Base_classprotected
computeMean(std::vector< double > &newAngles) (defined in Line)Lineprotected
coordinates_pub (defined in Line)Lineprotected
detection_pub (defined in Line)Lineprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
image_raw_sub (defined in Line)Lineprotected
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Line)Lineprotected
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
Line() (defined in Line)Line
loadParams() (defined in Base_class)Base_classvirtual
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Line)Linevirtual
spinThreadFront() (defined in Base_class)Base_classvirtual
task_done (defined in Line)Lineprotected
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classLine.html b/docs/html/classLine.html new file mode 100644 index 0000000..c1ac89d --- /dev/null +++ b/docs/html/classLine.html @@ -0,0 +1,332 @@ + + + + + + + +Anahita: Line Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +Protected Member Functions | +Protected Attributes | +List of all members
+
+
Line Class Reference
+
+
+
+Inheritance diagram for Line:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void spinThreadBottom ()
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadFront ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+virtual void loadParams ()
 
+void init ()
 
+ + + + + + + +

+Protected Member Functions

+void callback (vision_tasks::lineRangeConfig &config, double level)
 
+void imageCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+double computeMean (std::vector< double > &newAngles)
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Protected Attributes

+image_transport::Subscriber image_raw_sub
 
+ros::Publisher detection_pub
 
+ros::Publisher coordinates_pub
 
+std::string camera_frame_
 
+bool task_done = false
 
+ros::Publisher ang_pub
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classLine.png b/docs/html/classLine.png new file mode 100644 index 0000000..0fd2349 Binary files /dev/null and b/docs/html/classLine.png differ diff --git a/docs/html/classMS5837-members.html b/docs/html/classMS5837-members.html new file mode 100644 index 0000000..1fb41c2 --- /dev/null +++ b/docs/html/classMS5837-members.html @@ -0,0 +1,93 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
MS5837 Member List
+
+
+ +

This is the complete list of members for MS5837, including all inherited members.

+ + + + + + + + + + + + + + + +
altitude()MS5837
bar (defined in MS5837)MS5837static
depth()MS5837
init() (defined in MS5837)MS5837
mbar (defined in MS5837)MS5837static
MS5837() (defined in MS5837)MS5837
MS5837_02BA (defined in MS5837)MS5837static
MS5837_30BA (defined in MS5837)MS5837static
Pa (defined in MS5837)MS5837static
pressure(float conversion=1.0f)MS5837
read()MS5837
setFluidDensity(float density)MS5837
setModel(uint8_t model)MS5837
temperature()MS5837
+ + + + diff --git a/docs/html/classMS5837.html b/docs/html/classMS5837.html new file mode 100644 index 0000000..30c69c0 --- /dev/null +++ b/docs/html/classMS5837.html @@ -0,0 +1,253 @@ + + + + + + + +Anahita: MS5837 Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +Static Public Attributes | +List of all members
+
+
MS5837 Class Reference
+
+
+ + + + + + + + + + + + + + + + + + +

+Public Member Functions

+bool init ()
 
void setModel (uint8_t model)
 
void setFluidDensity (float density)
 
void read ()
 
float pressure (float conversion=1.0f)
 
float temperature ()
 
float depth ()
 
float altitude ()
 
+ + + + + + + + + + + +

+Static Public Attributes

+static const float Pa = 100.0f
 
+static const float bar = 0.001f
 
+static const float mbar = 1.0f
 
+static const uint8_t MS5837_30BA = 0
 
+static const uint8_t MS5837_02BA = 1
 
+

Member Function Documentation

+ +

◆ altitude()

+ +
+
+ + + + + + + +
float MS5837::altitude ()
+
+

Altitude returned in meters (valid for operation in air only).

+ +
+
+ +

◆ depth()

+ +
+
+ + + + + + + +
float MS5837::depth ()
+
+

Depth returned in meters (valid for operation in incompressible liquids only. Uses density that is set for fresh or seawater.

+ +
+
+ +

◆ pressure()

+ +
+
+ + + + + + + + +
float MS5837::pressure (float conversion = 1.0f)
+
+

Pressure returned in mbar or mbar*conversion rate.

+ +
+
+ +

◆ read()

+ +
+
+ + + + + + + +
void MS5837::read ()
+
+

The read from I2C takes up to 40 ms, so use sparingly is possible.

+ +
+
+ +

◆ setFluidDensity()

+ +
+
+ + + + + + + + +
void MS5837::setFluidDensity (float density)
+
+

Provide the density of the working fluid in kg/m^3. Default is for seawater. Should be 997 for freshwater.

+ +
+
+ +

◆ setModel()

+ +
+
+ + + + + + + + +
void MS5837::setModel (uint8_t model)
+
+

Set model of MS5837 sensor. Valid options are MS5837::MS5837_30BA (default) and MS5837::MS5837_02BA.

+ +
+
+ +

◆ temperature()

+ +
+
+ + + + + + + +
float MS5837::temperature ()
+
+

Temperature returned in deg C.

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classMarker-members.html b/docs/html/classMarker-members.html new file mode 100644 index 0000000..072143c --- /dev/null +++ b/docs/html/classMarker-members.html @@ -0,0 +1,146 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Marker Member List
+
+
+ +

This is the complete list of members for Marker, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in Marker)Markervirtual
Marker() (defined in Marker)Marker
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() override (defined in Marker)Markervirtual
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classMarker.html b/docs/html/classMarker.html new file mode 100644 index 0000000..2a514ff --- /dev/null +++ b/docs/html/classMarker.html @@ -0,0 +1,297 @@ + + + + + + + +Anahita: Marker Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
Marker Class Reference
+
+
+
+Inheritance diagram for Marker:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void loadParams () override
 
+virtual void spinThreadFront () override
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classMarker.png b/docs/html/classMarker.png new file mode 100644 index 0000000..a0d8c74 Binary files /dev/null and b/docs/html/classMarker.png differ diff --git a/docs/html/classMarkerDropper-members.html b/docs/html/classMarkerDropper-members.html new file mode 100644 index 0000000..f93f6c0 --- /dev/null +++ b/docs/html/classMarkerDropper-members.html @@ -0,0 +1,184 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
MarkerDropper Member List
+
+
+ +

This is the complete list of members for MarkerDropper, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_balanced_bilateral_iter_ (defined in MarkerDropper)MarkerDropperprotected
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_blue_filtered_pub (defined in MarkerDropper)MarkerDropperprotected
bottom_clahe_bilateral_iter_ (defined in MarkerDropper)MarkerDropperprotected
bottom_clahe_clip_ (defined in MarkerDropper)MarkerDropperprotected
bottom_clahe_grid_size_ (defined in MarkerDropper)MarkerDropperprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_denoise_h_ (defined in MarkerDropper)MarkerDropperprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_raw_sub (defined in MarkerDropper)MarkerDropperprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomCallback(vision_tasks::markerDropperBottomRangeConfig &config, double level) (defined in MarkerDropper)MarkerDropperprotected
bottomCallback(vision_tasks::markerDropperBottomRangeConfig &config, double level) (defined in MarkerDropper)MarkerDropperprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
camera_frame_ (defined in MarkerDropper)MarkerDropperprotected
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in MarkerDropper)MarkerDropperprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
findCenter() (defined in MarkerDropper)MarkerDropper
front_balanced_bilateral_iter_ (defined in MarkerDropper)MarkerDropperprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_blue_filtered_pub (defined in MarkerDropper)MarkerDropperprotected
front_canny_kernel_size_ (defined in MarkerDropper)MarkerDropperprotected
front_canny_threshold_high_ (defined in MarkerDropper)MarkerDropperprotected
front_canny_threshold_low_ (defined in MarkerDropper)MarkerDropperprotected
front_clahe_bilateral_iter_ (defined in MarkerDropper)MarkerDropperprotected
front_clahe_clip_ (defined in MarkerDropper)MarkerDropperprotected
front_clahe_grid_size_ (defined in MarkerDropper)MarkerDropperprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_denoise_h_ (defined in MarkerDropper)MarkerDropperprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_gate_angle_tolerance_ (defined in MarkerDropper)MarkerDropperprotected
front_gate_distance_tolerance_ (defined in MarkerDropper)MarkerDropperprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_hough_angle_tolerance_ (defined in MarkerDropper)MarkerDropperprotected
front_hough_maxgap_ (defined in MarkerDropper)MarkerDropperprotected
front_hough_minline_ (defined in MarkerDropper)MarkerDropperprotected
front_hough_threshold_ (defined in MarkerDropper)MarkerDropperprotected
front_image_raw_sub (defined in MarkerDropper)MarkerDropperprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontCallback(vision_tasks::markerDropperFrontRangeConfig &config, double level) (defined in MarkerDropper)MarkerDropperprotected
frontCallback(vision_tasks::markerDropperFrontRangeConfig &config, double level) (defined in MarkerDropper)MarkerDropperprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
image_marked (defined in MarkerDropper)MarkerDropper
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in MarkerDropper)MarkerDropperprotected
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in MarkerDropper)MarkerDropperprotected
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in MarkerDropper)MarkerDropperprotected
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in MarkerDropper)MarkerDropperprotected
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in MarkerDropper)MarkerDroppervirtual
MarkerDropper() (defined in MarkerDropper)MarkerDropper
MarkerDropper() (defined in MarkerDropper)MarkerDropper
MarkerDropper() (defined in MarkerDropper)MarkerDropper
nh (defined in Base_class)Base_class
preProcess(cv::Mat &temp_src) (defined in MarkerDropper)MarkerDropper
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() override (defined in MarkerDropper)MarkerDroppervirtual
spinThreadBottom() (defined in MarkerDropper)MarkerDroppervirtual
spinThreadBottom() (defined in MarkerDropper)MarkerDroppervirtual
spinThreadFront() (defined in MarkerDropper)MarkerDroppervirtual
spinThreadFront() (defined in MarkerDropper)MarkerDroppervirtual
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classMarkerDropper.html b/docs/html/classMarkerDropper.html new file mode 100644 index 0000000..cb3f40b --- /dev/null +++ b/docs/html/classMarkerDropper.html @@ -0,0 +1,427 @@ + + + + + + + +Anahita: MarkerDropper Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +Public Attributes | +Protected Member Functions | +Protected Attributes | +List of all members
+
+
MarkerDropper Class Reference
+
+
+
+Inheritance diagram for MarkerDropper:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void loadParams () override
 
+virtual void spinThreadBottom () override
 
+void preProcess (cv::Mat &temp_src)
 
+cv::Point findCenter ()
 
+void spinThreadBottom ()
 
+void spinThreadFront ()
 
+void spinThreadBottom ()
 
+void spinThreadFront ()
 
- Public Member Functions inherited from Base_class
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Attributes

+cv::Mat image_marked
 
- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
+ + + + + + + + + + + + + + + + + +

+Protected Member Functions

+void frontCallback (vision_tasks::markerDropperFrontRangeConfig &config, double level)
 
+void bottomCallback (vision_tasks::markerDropperBottomRangeConfig &config, double level)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void frontCallback (vision_tasks::markerDropperFrontRangeConfig &config, double level)
 
+void bottomCallback (vision_tasks::markerDropperBottomRangeConfig &config, double level)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Protected Attributes

+image_transport::Publisher bottom_blue_filtered_pub
 
+image_transport::Publisher front_blue_filtered_pub
 
+image_transport::Subscriber front_image_raw_sub
 
+image_transport::Subscriber bottom_image_raw_sub
 
+ros::Publisher detection_pub
 
+std::string camera_frame_
 
+double front_clahe_clip_ = 4.0
 
+int front_clahe_grid_size_ = 8
 
+int front_clahe_bilateral_iter_ = 8
 
+int front_balanced_bilateral_iter_ = 4
 
+double front_denoise_h_ = 10.0
 
+int front_canny_threshold_low_ = 0
 
+int front_canny_threshold_high_ = 1000
 
+int front_canny_kernel_size_ = 3
 
+int front_hough_threshold_ = 0
 
+int front_hough_minline_ = 0
 
+int front_hough_maxgap_ = 0
 
+double front_hough_angle_tolerance_ = 0.0
 
+double front_gate_distance_tolerance_ = 50.0
 
+double front_gate_angle_tolerance_ = 0.0
 
+double bottom_clahe_clip_ = 4.0
 
+int bottom_clahe_grid_size_ = 8
 
+int bottom_clahe_bilateral_iter_ = 8
 
+int bottom_balanced_bilateral_iter_ = 4
 
+double bottom_denoise_h_ = 10.0
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classMarkerDropper.png b/docs/html/classMarkerDropper.png new file mode 100644 index 0000000..eb453fe Binary files /dev/null and b/docs/html/classMarkerDropper.png differ diff --git a/docs/html/classOctagon-members.html b/docs/html/classOctagon-members.html new file mode 100644 index 0000000..a63274a --- /dev/null +++ b/docs/html/classOctagon-members.html @@ -0,0 +1,171 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Octagon Member List
+
+
+ +

This is the complete list of members for Octagon, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
blue_filtered_pub (defined in Octagon)Octagonprotected
bottom_balanced_bilateral_iter_ (defined in Octagon)Octagonprotected
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_clahe_bilateral_iter_ (defined in Octagon)Octagonprotected
bottom_clahe_clip_ (defined in Octagon)Octagonprotected
bottom_clahe_grid_size_ (defined in Octagon)Octagonprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_denoise_h_ (defined in Octagon)Octagonprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomCallback(vision_tasks::octagonBottomRangeConfig &config, double level) (defined in Octagon)Octagonprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
camera_frame_ (defined in Octagon)Octagonprotected
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_balanced_bilateral_iter_ (defined in Octagon)Octagonprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_canny_kernel_size_ (defined in Octagon)Octagonprotected
front_canny_threshold_high_ (defined in Octagon)Octagonprotected
front_canny_threshold_low_ (defined in Octagon)Octagonprotected
front_clahe_bilateral_iter_ (defined in Octagon)Octagonprotected
front_clahe_clip_ (defined in Octagon)Octagonprotected
front_clahe_grid_size_ (defined in Octagon)Octagonprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_denoise_h_ (defined in Octagon)Octagonprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_gate_angle_tolerance_ (defined in Octagon)Octagonprotected
front_gate_distance_tolerance_ (defined in Octagon)Octagonprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_hough_angle_tolerance_ (defined in Octagon)Octagonprotected
front_hough_maxgap_ (defined in Octagon)Octagonprotected
front_hough_minline_ (defined in Octagon)Octagonprotected
front_hough_threshold_ (defined in Octagon)Octagonprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontCallback(vision_tasks::octagonFrontRangeConfig &config, double level) (defined in Octagon)Octagonprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
image_raw_sub (defined in Octagon)Octagonprotected
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Octagon)Octagonprotected
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Octagon)Octagonprotected
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() (defined in Base_class)Base_classvirtual
nh (defined in Base_class)Base_class
Octagon() (defined in Octagon)Octagon
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Octagon)Octagonvirtual
spinThreadFront() (defined in Octagon)Octagonvirtual
task_done (defined in Octagon)Octagonprotected
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classOctagon.html b/docs/html/classOctagon.html new file mode 100644 index 0000000..2bfb542 --- /dev/null +++ b/docs/html/classOctagon.html @@ -0,0 +1,386 @@ + + + + + + + +Anahita: Octagon Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +Protected Member Functions | +Protected Attributes | +List of all members
+
+
Octagon Class Reference
+
+
+
+Inheritance diagram for Octagon:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void spinThreadBottom ()
 
+void spinThreadFront ()
 
- Public Member Functions inherited from Base_class
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+virtual void loadParams ()
 
+void init ()
 
+ + + + + + + + + +

+Protected Member Functions

+void frontCallback (vision_tasks::octagonFrontRangeConfig &config, double level)
 
+void bottomCallback (vision_tasks::octagonBottomRangeConfig &config, double level)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Protected Attributes

+image_transport::Publisher blue_filtered_pub
 
+image_transport::Subscriber image_raw_sub
 
+std::string camera_frame_
 
+double front_clahe_clip_ = 4.0
 
+int front_clahe_grid_size_ = 8
 
+int front_clahe_bilateral_iter_ = 8
 
+int front_balanced_bilateral_iter_ = 4
 
+double front_denoise_h_ = 10.0
 
+int front_canny_threshold_low_ = 0
 
+int front_canny_threshold_high_ = 1000
 
+int front_canny_kernel_size_ = 3
 
+int front_hough_threshold_ = 0
 
+int front_hough_minline_ = 0
 
+int front_hough_maxgap_ = 0
 
+double front_hough_angle_tolerance_ = 0.0
 
+double front_gate_distance_tolerance_ = 50.0
 
+double front_gate_angle_tolerance_ = 0.0
 
+double bottom_clahe_clip_ = 4.0
 
+int bottom_clahe_grid_size_ = 8
 
+int bottom_clahe_bilateral_iter_ = 8
 
+int bottom_balanced_bilateral_iter_ = 4
 
+double bottom_denoise_h_ = 10.0
 
+bool task_done = false
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classOctagon.png b/docs/html/classOctagon.png new file mode 100644 index 0000000..a8a3161 Binary files /dev/null and b/docs/html/classOctagon.png differ diff --git a/docs/html/classPID_1_1PIDRegulator_1_1PIDRegulator-members.html b/docs/html/classPID_1_1PIDRegulator_1_1PIDRegulator-members.html new file mode 100644 index 0000000..a5fa81f --- /dev/null +++ b/docs/html/classPID_1_1PIDRegulator_1_1PIDRegulator-members.html @@ -0,0 +1,93 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
PID.PIDRegulator.PIDRegulator Member List
+
+
+ +

This is the complete list of members for PID.PIDRegulator.PIDRegulator, including all inherited members.

+ + + + + + + + + + + +
__init__(self, p, i, d, sat) (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
__str__(self) (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
d (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
i (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
integral (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
p (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
prev_err (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
prev_t (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
regulate(self, err, t) (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
sat (defined in PID.PIDRegulator.PIDRegulator)PID.PIDRegulator.PIDRegulator
+ + + + diff --git a/docs/html/classPID_1_1PIDRegulator_1_1PIDRegulator.html b/docs/html/classPID_1_1PIDRegulator_1_1PIDRegulator.html new file mode 100644 index 0000000..4ca6de2 --- /dev/null +++ b/docs/html/classPID_1_1PIDRegulator_1_1PIDRegulator.html @@ -0,0 +1,125 @@ + + + + + + + +Anahita: PID.PIDRegulator.PIDRegulator Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
PID.PIDRegulator.PIDRegulator Class Reference
+
+
+ + + + + + + + +

+Public Member Functions

+def __init__ (self, p, i, d, sat)
 
+def __str__ (self)
 
+def regulate (self, err, t)
 
+ + + + + + + + + + + + + + + +

+Public Attributes

p
 
i
 
d
 
sat
 
integral
 
prev_err
 
prev_t
 
+

Detailed Description

+
A very basic 1D PID Regulator.

The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classPathMarker-members.html b/docs/html/classPathMarker-members.html new file mode 100644 index 0000000..ba910d2 --- /dev/null +++ b/docs/html/classPathMarker-members.html @@ -0,0 +1,147 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
PathMarker Member List
+
+
+ +

This is the complete list of members for PathMarker, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in PathMarker)PathMarkervirtual
markerAngle(master_layer::RequestMarkerAngle::Request &req, master_layer::RequestMarkerAngle::Response &res) (defined in PathMarker)PathMarker
nh (defined in Base_class)Base_class
PathMarker() (defined in PathMarker)PathMarker
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() override (defined in PathMarker)PathMarkervirtual
spinThreadFront() (defined in Base_class)Base_classvirtual
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classPathMarker.html b/docs/html/classPathMarker.html new file mode 100644 index 0000000..6e4143d --- /dev/null +++ b/docs/html/classPathMarker.html @@ -0,0 +1,300 @@ + + + + + + + +Anahita: PathMarker Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
PathMarker Class Reference
+
+
+
+Inheritance diagram for PathMarker:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void loadParams () override
 
+virtual void spinThreadBottom () override
 
+bool markerAngle (master_layer::RequestMarkerAngle::Request &req, master_layer::RequestMarkerAngle::Response &res)
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadFront ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classPathMarker.png b/docs/html/classPathMarker.png new file mode 100644 index 0000000..487e3c3 Binary files /dev/null and b/docs/html/classPathMarker.png differ diff --git a/docs/html/classPinger-members.html b/docs/html/classPinger-members.html new file mode 100644 index 0000000..cd8398d --- /dev/null +++ b/docs/html/classPinger-members.html @@ -0,0 +1,149 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Pinger Member List
+
+
+ +

This is the complete list of members for Pinger, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTarget(master_layer::PingerBottomTarget::Request &req, master_layer::PingerBottomTarget::Response &resp) (defined in Pinger)Pinger
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTarget(master_layer::PingerFrontTarget::Request &req, master_layer::PingerFrontTarget::Response &resp) (defined in Pinger)Pinger
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
getContourCenter(const std::vector< cv::Point > &contour) (defined in Pinger)Pinger
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in Pinger)Pingervirtual
nh (defined in Base_class)Base_class
Pinger() (defined in Pinger)Pinger
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() override (defined in Pinger)Pingervirtual
spinThreadFront() override (defined in Pinger)Pingervirtual
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classPinger.html b/docs/html/classPinger.html new file mode 100644 index 0000000..6295af5 --- /dev/null +++ b/docs/html/classPinger.html @@ -0,0 +1,306 @@ + + + + + + + +Anahita: Pinger Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
Pinger Class Reference
+
+
+
+Inheritance diagram for Pinger:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void loadParams () override
 
+void spinThreadFront () override
 
+void spinThreadBottom () override
 
+cv::Point getContourCenter (const std::vector< cv::Point > &contour)
 
+bool bottomTarget (master_layer::PingerBottomTarget::Request &req, master_layer::PingerBottomTarget::Response &resp)
 
+bool frontTarget (master_layer::PingerFrontTarget::Request &req, master_layer::PingerFrontTarget::Response &resp)
 
- Public Member Functions inherited from Base_class
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classPinger.png b/docs/html/classPinger.png new file mode 100644 index 0000000..fdb81e8 Binary files /dev/null and b/docs/html/classPinger.png differ diff --git a/docs/html/classPositionControlUnderactuated_1_1PositionControllerNode-members.html b/docs/html/classPositionControlUnderactuated_1_1PositionControllerNode-members.html new file mode 100644 index 0000000..22d1482 --- /dev/null +++ b/docs/html/classPositionControlUnderactuated_1_1PositionControllerNode-members.html @@ -0,0 +1,99 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
PositionControlUnderactuated.PositionControllerNode Member List
+
+
+ +

This is the complete list of members for PositionControlUnderactuated.PositionControllerNode, including all inherited members.

+ + + + + + + + + + + + + + + + + +
__init__(self) (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
cmd_pose_callback(self, msg)PositionControlUnderactuated.PositionControllerNode
config (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
config_callback(self, config, level)PositionControlUnderactuated.PositionControllerNode
initialized (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
listener (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
odometry_callback(self, msg)PositionControlUnderactuated.PositionControllerNode
pid_depth (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
pid_forward (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
pid_heading (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
pos_des (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
pub_cmd_vel (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
quat_des (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
srv_reconfigure (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
sub_cmd_pose (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
sub_odometry (defined in PositionControlUnderactuated.PositionControllerNode)PositionControlUnderactuated.PositionControllerNode
+ + + + diff --git a/docs/html/classPositionControlUnderactuated_1_1PositionControllerNode.html b/docs/html/classPositionControlUnderactuated_1_1PositionControllerNode.html new file mode 100644 index 0000000..a677b2a --- /dev/null +++ b/docs/html/classPositionControlUnderactuated_1_1PositionControllerNode.html @@ -0,0 +1,230 @@ + + + + + + + +Anahita: PositionControlUnderactuated.PositionControllerNode Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
PositionControlUnderactuated.PositionControllerNode Class Reference
+
+
+ + + + + + + + + + +

+Public Member Functions

+def __init__ (self)
 
def cmd_pose_callback (self, msg)
 
def odometry_callback (self, msg)
 
def config_callback (self, config, level)
 
+ + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Attributes

config
 
pos_des
 
quat_des
 
initialized
 
pid_depth
 
pid_heading
 
pid_forward
 
listener
 
sub_cmd_pose
 
sub_odometry
 
pub_cmd_vel
 
srv_reconfigure
 
+

Member Function Documentation

+ +

◆ cmd_pose_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def PositionControlUnderactuated.PositionControllerNode.cmd_pose_callback ( self,
 msg 
)
+
+
Handle updated set pose callback.
+
+
+ +

◆ config_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
def PositionControlUnderactuated.PositionControllerNode.config_callback ( self,
 config,
 level 
)
+
+
Handle updated configuration values.
+
+
+ +

◆ odometry_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def PositionControlUnderactuated.PositionControllerNode.odometry_callback ( self,
 msg 
)
+
+
Handle updated measured velocity callback.
+
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classPositionControl_1_1PositionControllerNode-members.html b/docs/html/classPositionControl_1_1PositionControllerNode-members.html new file mode 100644 index 0000000..228c7e6 --- /dev/null +++ b/docs/html/classPositionControl_1_1PositionControllerNode-members.html @@ -0,0 +1,97 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
PositionControl.PositionControllerNode Member List
+
+
+ +

This is the complete list of members for PositionControl.PositionControllerNode, including all inherited members.

+ + + + + + + + + + + + + + + +
__init__(self) (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
cmd_pose_callback(self, msg)PositionControl.PositionControllerNode
config (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
config_callback(self, config, level)PositionControl.PositionControllerNode
initialized (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
odometry_callback(self, msg)PositionControl.PositionControllerNode
pid_pos (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
pid_rot (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
pos_des (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
pub_cmd_vel (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
quat_des (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
srv_reconfigure (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
sub_cmd_pose (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
sub_odometry (defined in PositionControl.PositionControllerNode)PositionControl.PositionControllerNode
+ + + + diff --git a/docs/html/classPositionControl_1_1PositionControllerNode.html b/docs/html/classPositionControl_1_1PositionControllerNode.html new file mode 100644 index 0000000..d8dc5ae --- /dev/null +++ b/docs/html/classPositionControl_1_1PositionControllerNode.html @@ -0,0 +1,224 @@ + + + + + + + +Anahita: PositionControl.PositionControllerNode Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
PositionControl.PositionControllerNode Class Reference
+
+
+ + + + + + + + + + +

+Public Member Functions

+def __init__ (self)
 
def cmd_pose_callback (self, msg)
 
def odometry_callback (self, msg)
 
def config_callback (self, config, level)
 
+ + + + + + + + + + + + + + + + + + + + + +

+Public Attributes

config
 
pos_des
 
quat_des
 
initialized
 
pid_rot
 
pid_pos
 
sub_cmd_pose
 
sub_odometry
 
pub_cmd_vel
 
srv_reconfigure
 
+

Member Function Documentation

+ +

◆ cmd_pose_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def PositionControl.PositionControllerNode.cmd_pose_callback ( self,
 msg 
)
+
+
Handle updated set pose callback.
+
+
+ +

◆ config_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
def PositionControl.PositionControllerNode.config_callback ( self,
 config,
 level 
)
+
+
Handle updated configuration values.
+
+
+ +

◆ odometry_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def PositionControl.PositionControllerNode.odometry_callback ( self,
 msg 
)
+
+
Handle updated measured velocity callback.
+
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classStartGate-members.html b/docs/html/classStartGate-members.html new file mode 100644 index 0000000..af91431 --- /dev/null +++ b/docs/html/classStartGate-members.html @@ -0,0 +1,147 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
StartGate Member List
+
+
+ +

This is the complete list of members for StartGate, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
findGateCenter(cv::Mat &thres_img) (defined in StartGate)StartGate
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in StartGate)StartGatevirtual
nh (defined in Base_class)Base_class
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() override (defined in StartGate)StartGatevirtual
StartGate() (defined in StartGate)StartGate
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classStartGate.html b/docs/html/classStartGate.html new file mode 100644 index 0000000..12ced78 --- /dev/null +++ b/docs/html/classStartGate.html @@ -0,0 +1,300 @@ + + + + + + + +Anahita: StartGate Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
StartGate Class Reference
+
+
+
+Inheritance diagram for StartGate:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void loadParams () override
 
+void spinThreadFront () override
 
+cv::Point findGateCenter (cv::Mat &thres_img)
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classStartGate.png b/docs/html/classStartGate.png new file mode 100644 index 0000000..ab87c17 Binary files /dev/null and b/docs/html/classStartGate.png differ diff --git a/docs/html/classTest.html b/docs/html/classTest.html new file mode 100644 index 0000000..2a4d937 --- /dev/null +++ b/docs/html/classTest.html @@ -0,0 +1,111 @@ + + + + + + + +Anahita: Test Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Test Class Reference
+
+
+ +

This is a test class. *. + More...

+

Detailed Description

+

This is a test class. *.

+ +

starts brief description

+

starts detailed description

+
Parameters
+ + + + + + +
'['dir']'<parameter-name> { parameter description } Starts a parameter description for a function parameter with name <parameter-name>, followed by a description of the parameter. The
commandhas an optional attribute, dir, specifying the direction of the parameter. Possible values are "[in]", "[in,out]", and "[out]", note the [square] brackets in this description. When a parameter is both input and output, [in,out] is used as attribute. Ex- /*!
    +
  • Copies bytes from a source memory area to a destination memory area,
  • +
  • where both areas may not overlap.
  • +
  • +
+
[out]destThe memory area to copy to.
    +
  • +
+
[in]srcThe memory area to copy from.
    +
  • +
+
[in]nThe number of bytes to copy */ void memcpy(void *dest, const void *src, size_t n);
+
+
+

Link to official documentation of all the commands http://www.doxygen.nl/manual/commands.html

+

The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classTestGate-members.html b/docs/html/classTestGate-members.html new file mode 100644 index 0000000..403d949 --- /dev/null +++ b/docs/html/classTestGate-members.html @@ -0,0 +1,148 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
TestGate Member List
+
+
+ +

This is the complete list of members for TestGate, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
getNormal(master_layer::TargetNormal::Request &req, master_layer::TargetNormal::Response &resp) (defined in TestGate)TestGate
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in TestGate)TestGatevirtual
nh (defined in Base_class)Base_class
rectCB(const sensor_msgs::Image::ConstPtr &msg) (defined in TestGate)TestGate
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() override (defined in TestGate)TestGatevirtual
TestGate() (defined in TestGate)TestGate
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classTestGate.html b/docs/html/classTestGate.html new file mode 100644 index 0000000..c6474fc --- /dev/null +++ b/docs/html/classTestGate.html @@ -0,0 +1,303 @@ + + + + + + + +Anahita: TestGate Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
TestGate Class Reference
+
+
+
+Inheritance diagram for TestGate:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void loadParams () override
 
+void spinThreadFront () override
 
+void rectCB (const sensor_msgs::Image::ConstPtr &msg)
 
+bool getNormal (master_layer::TargetNormal::Request &req, master_layer::TargetNormal::Response &resp)
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classTestGate.png b/docs/html/classTestGate.png new file mode 100644 index 0000000..f5d3668 Binary files /dev/null and b/docs/html/classTestGate.png differ diff --git a/docs/html/classTorpedo-members.html b/docs/html/classTorpedo-members.html new file mode 100644 index 0000000..c69b48c --- /dev/null +++ b/docs/html/classTorpedo-members.html @@ -0,0 +1,153 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
Torpedo Member List
+
+
+ +

This is the complete list of members for Torpedo, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
changeTorpedoHole(master_layer::ChangeTorpedoHole::Request &req, master_layer::ChangeTorpedoHole::Response &resp) (defined in Torpedo)Torpedo
close_task (defined in Base_class)Base_classprotected
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
findCircles(cv::Mat &src_img, cv::Mat &thres_img, double circle_threshold) (defined in Torpedo)Torpedo
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
init() (defined in Base_class)Base_class
InitTracker(cv::Mat &src_img, cv::Mat &thres_img, double circle_threshold) (defined in Torpedo)Torpedo
it (defined in Base_class)Base_class
loadParams() override (defined in Torpedo)Torpedovirtual
nh (defined in Base_class)Base_class
recogniseHoles(cv::Mat &thres_img) (defined in Torpedo)Torpedo
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() override (defined in Torpedo)Torpedovirtual
threshROI(const cv::Rect2d &bounding_rect, const cv::Mat &img, int padding) (defined in Torpedo)Torpedo
Torpedo() (defined in Torpedo)Torpedo
updateCoordinates(std::vector< cv::Point > points) (defined in Torpedo)Torpedo
updateTracker(cv::Mat &src_img) (defined in Torpedo)Torpedo
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classTorpedo.html b/docs/html/classTorpedo.html new file mode 100644 index 0000000..ea0f10a --- /dev/null +++ b/docs/html/classTorpedo.html @@ -0,0 +1,319 @@ + + + + + + + +Anahita: Torpedo Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
Torpedo Class Reference
+
+
+
+Inheritance diagram for Torpedo:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+virtual void loadParams () override
 
+virtual void spinThreadFront () override
 
+void findCircles (cv::Mat &src_img, cv::Mat &thres_img, double circle_threshold)
 
+void InitTracker (cv::Mat &src_img, cv::Mat &thres_img, double circle_threshold)
 
+void updateTracker (cv::Mat &src_img)
 
+cv::Point2f threshROI (const cv::Rect2d &bounding_rect, const cv::Mat &img, int padding)
 
+void recogniseHoles (cv::Mat &thres_img)
 
+void updateCoordinates (std::vector< cv::Point > points)
 
+bool changeTorpedoHole (master_layer::ChangeTorpedoHole::Request &req, master_layer::ChangeTorpedoHole::Response &resp)
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classTorpedo.png b/docs/html/classTorpedo.png new file mode 100644 index 0000000..fb31d86 Binary files /dev/null and b/docs/html/classTorpedo.png differ diff --git a/docs/html/classTriangularBuoy-members.html b/docs/html/classTriangularBuoy-members.html new file mode 100644 index 0000000..bed9a6f --- /dev/null +++ b/docs/html/classTriangularBuoy-members.html @@ -0,0 +1,151 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
TriangularBuoy Member List
+
+
+ +

This is the complete list of members for TriangularBuoy, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Base_class() (defined in Base_class)Base_class
blackoutCB(master_layer::GetBlackoutTime::Request &req, master_layer::GetBlackoutTime::Response &res) (defined in TriangularBuoy)TriangularBuoy
bottom_bilateral_iter_ (defined in Base_class)Base_classprotected
bottom_closing_iter_ (defined in Base_class)Base_classprotected
bottom_closing_mat_point_ (defined in Base_class)Base_classprotected
bottom_high_b_ (defined in Base_class)Base_classprotected
bottom_high_g_ (defined in Base_class)Base_classprotected
bottom_high_r_ (defined in Base_class)Base_classprotected
bottom_image_sub (defined in Base_class)Base_classprotected
bottom_low_b_ (defined in Base_class)Base_classprotected
bottom_low_g_ (defined in Base_class)Base_classprotected
bottom_low_r_ (defined in Base_class)Base_classprotected
bottom_marked_pub (defined in Base_class)Base_classprotected
bottom_opening_iter_ (defined in Base_class)Base_classprotected
bottom_opening_mat_point_ (defined in Base_class)Base_classprotected
bottom_thresholded_pub (defined in Base_class)Base_classprotected
bottom_x_coordinate (defined in Base_class)Base_class
bottom_x_coordinate_pub (defined in Base_class)Base_classprotected
bottom_y_coordinate (defined in Base_class)Base_class
bottom_y_coordinate_pub (defined in Base_class)Base_classprotected
bottom_z_coordinate (defined in Base_class)Base_class
bottom_z_coordinate_pub (defined in Base_class)Base_classprotected
bottomTaskHandling(bool status) (defined in Base_class)Base_class
close_task (defined in Base_class)Base_classprotected
depthCallback(const geometry_msgs::Point msg) (defined in TriangularBuoy)TriangularBuoy
depthRequest(master_layer::GetMaxDepth::Request &req, master_layer::GetMaxDepth::Response &res) (defined in TriangularBuoy)TriangularBuoy
detection_pub (defined in Base_class)Base_classprotected
enhanced_image (defined in Base_class)Base_class
enhanced_image_sub (defined in Base_class)Base_classprotected
findCenter() (defined in TriangularBuoy)TriangularBuoy
front_bilateral_iter_ (defined in Base_class)Base_classprotected
front_closing_iter_ (defined in Base_class)Base_classprotected
front_closing_mat_point_ (defined in Base_class)Base_classprotected
front_edges_pub (defined in Base_class)Base_classprotected
front_high_b_ (defined in Base_class)Base_classprotected
front_high_g_ (defined in Base_class)Base_classprotected
front_high_r_ (defined in Base_class)Base_classprotected
front_image_sub (defined in Base_class)Base_classprotected
front_low_b_ (defined in Base_class)Base_classprotected
front_low_g_ (defined in Base_class)Base_classprotected
front_low_r_ (defined in Base_class)Base_classprotected
front_marked_pub (defined in Base_class)Base_classprotected
front_opening_iter_ (defined in Base_class)Base_classprotected
front_opening_mat_point_ (defined in Base_class)Base_classprotected
front_thresholded_pub (defined in Base_class)Base_classprotected
front_x_coordinate (defined in Base_class)Base_class
front_x_coordinate_pub (defined in Base_class)Base_classprotected
front_y_coordinate (defined in Base_class)Base_class
front_y_coordinate_pub (defined in Base_class)Base_classprotected
front_z_coordinate (defined in Base_class)Base_class
front_z_coordinate_pub (defined in Base_class)Base_classprotected
frontTaskHandling(bool status) (defined in Base_class)Base_class
fusionCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
image_bottom (defined in Base_class)Base_class
image_bottom_marked (defined in Base_class)Base_class
image_bottom_thresholded (defined in Base_class)Base_class
image_front (defined in Base_class)Base_class
image_front_marked (defined in Base_class)Base_class
image_front_thresholded (defined in Base_class)Base_class
imageBottomCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
imageFrontCallback(const sensor_msgs::Image::ConstPtr &msg) (defined in Base_class)Base_class
it (defined in Base_class)Base_class
loadParams() override (defined in TriangularBuoy)TriangularBuoyvirtual
nh (defined in Base_class)Base_class
preProcess(cv::Mat &temp_src) (defined in TriangularBuoy)TriangularBuoy
rectCB(const sensor_msgs::Image::ConstPtr &msg) (defined in TriangularBuoy)TriangularBuoy
spin_thread_bottom (defined in Base_class)Base_class
spin_thread_front (defined in Base_class)Base_class
spinThreadBottom() (defined in Base_class)Base_classvirtual
spinThreadFront() override (defined in TriangularBuoy)TriangularBuoyvirtual
TriangularBuoy() (defined in TriangularBuoy)TriangularBuoy
vision_mutex (defined in Base_class)Base_class
+ + + + diff --git a/docs/html/classTriangularBuoy.html b/docs/html/classTriangularBuoy.html new file mode 100644 index 0000000..6abc792 --- /dev/null +++ b/docs/html/classTriangularBuoy.html @@ -0,0 +1,315 @@ + + + + + + + +Anahita: TriangularBuoy Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
TriangularBuoy Class Reference
+
+
+
+Inheritance diagram for TriangularBuoy:
+
+
+ + +Base_class + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

+void loadParams () override
 
+void spinThreadFront () override
 
+void preProcess (cv::Mat &temp_src)
 
+cv::Point findCenter ()
 
+void depthCallback (const geometry_msgs::Point msg)
 
+bool depthRequest (master_layer::GetMaxDepth::Request &req, master_layer::GetMaxDepth::Response &res)
 
+bool blackoutCB (master_layer::GetBlackoutTime::Request &req, master_layer::GetBlackoutTime::Response &res)
 
+void rectCB (const sensor_msgs::Image::ConstPtr &msg)
 
- Public Member Functions inherited from Base_class
+virtual void spinThreadBottom ()
 
+void bottomTaskHandling (bool status)
 
+void frontTaskHandling (bool status)
 
+void imageFrontCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void imageBottomCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void fusionCallback (const sensor_msgs::Image::ConstPtr &msg)
 
+void init ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Public Attributes inherited from Base_class
+ros::NodeHandle nh
 
+image_transport::ImageTransport it
 
+std_msgs::Float32 front_x_coordinate
 
+std_msgs::Float32 front_y_coordinate
 
+std_msgs::Float32 front_z_coordinate
 
+std_msgs::Float32 bottom_x_coordinate
 
+std_msgs::Float32 bottom_y_coordinate
 
+std_msgs::Float32 bottom_z_coordinate
 
+cv::Mat image_front
 
+cv::Mat image_bottom
 
+cv::Mat image_front_marked
 
+cv::Mat image_bottom_marked
 
+cv::Mat image_front_thresholded
 
+cv::Mat image_bottom_thresholded
 
+cv::Mat enhanced_image
 
+boost::thread * spin_thread_bottom
 
+boost::thread * spin_thread_front
 
+std::mutex vision_mutex
 
- Protected Attributes inherited from Base_class
+int front_low_g_
 
+int front_high_g_
 
+int front_low_r_
 
+int front_high_r_
 
+int front_low_b_
 
+int front_high_b_
 
+int front_opening_mat_point_
 
+int front_opening_iter_
 
+int front_closing_mat_point_
 
+int front_closing_iter_
 
+int front_bilateral_iter_
 
+int bottom_low_g_
 
+int bottom_low_r_
 
+int bottom_low_b_
 
+int bottom_high_g_
 
+int bottom_high_r_
 
+int bottom_high_b_
 
+int bottom_closing_mat_point_
 
+int bottom_closing_iter_
 
+int bottom_opening_iter_
 
+int bottom_opening_mat_point_
 
+int bottom_bilateral_iter_
 
+bool close_task = false
 
+image_transport::Subscriber front_image_sub
 
+image_transport::Subscriber bottom_image_sub
 
+image_transport::Subscriber enhanced_image_sub
 
+image_transport::Publisher bottom_thresholded_pub
 
+image_transport::Publisher bottom_marked_pub
 
+image_transport::Publisher front_thresholded_pub
 
+image_transport::Publisher front_marked_pub
 
+image_transport::Publisher front_edges_pub
 
+ros::Publisher front_x_coordinate_pub
 
+ros::Publisher front_y_coordinate_pub
 
+ros::Publisher front_z_coordinate_pub
 
+ros::Publisher bottom_x_coordinate_pub
 
+ros::Publisher bottom_y_coordinate_pub
 
+ros::Publisher bottom_z_coordinate_pub
 
+ros::Publisher detection_pub
 
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classTriangularBuoy.png b/docs/html/classTriangularBuoy.png new file mode 100644 index 0000000..ccbd994 Binary files /dev/null and b/docs/html/classTriangularBuoy.png differ diff --git a/docs/html/classVelocityControl_1_1VelocityControllerNode-members.html b/docs/html/classVelocityControl_1_1VelocityControllerNode-members.html new file mode 100644 index 0000000..3d456b7 --- /dev/null +++ b/docs/html/classVelocityControl_1_1VelocityControllerNode-members.html @@ -0,0 +1,96 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
VelocityControl.VelocityControllerNode Member List
+
+
+ +

This is the complete list of members for VelocityControl.VelocityControllerNode, including all inherited members.

+ + + + + + + + + + + + + + +
__init__(self) (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
cmd_vel_callback(self, msg)VelocityControl.VelocityControllerNode
config (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
config_callback(self, config, level)VelocityControl.VelocityControllerNode
odometry_callback(self, msg)VelocityControl.VelocityControllerNode
pid_angular (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
pid_linear (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
pub_cmd_accel (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
srv_reconfigure (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
sub_cmd_vel (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
sub_odometry (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
v_angular_des (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
v_linear_des (defined in VelocityControl.VelocityControllerNode)VelocityControl.VelocityControllerNode
+ + + + diff --git a/docs/html/classVelocityControl_1_1VelocityControllerNode.html b/docs/html/classVelocityControl_1_1VelocityControllerNode.html new file mode 100644 index 0000000..640a404 --- /dev/null +++ b/docs/html/classVelocityControl_1_1VelocityControllerNode.html @@ -0,0 +1,221 @@ + + + + + + + +Anahita: VelocityControl.VelocityControllerNode Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
VelocityControl.VelocityControllerNode Class Reference
+
+
+ + + + + + + + + + +

+Public Member Functions

+def __init__ (self)
 
def cmd_vel_callback (self, msg)
 
def odometry_callback (self, msg)
 
def config_callback (self, config, level)
 
+ + + + + + + + + + + + + + + + + + + +

+Public Attributes

config
 
v_linear_des
 
v_angular_des
 
pid_angular
 
pid_linear
 
sub_cmd_vel
 
sub_odometry
 
pub_cmd_accel
 
srv_reconfigure
 
+

Member Function Documentation

+ +

◆ cmd_vel_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def VelocityControl.VelocityControllerNode.cmd_vel_callback ( self,
 msg 
)
+
+
Handle updated set velocity callback.
+
+
+ +

◆ config_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
def VelocityControl.VelocityControllerNode.config_callback ( self,
 config,
 level 
)
+
+
Handle updated configuration values.
+
+
+ +

◆ odometry_callback()

+ +
+
+ + + + + + + + + + + + + + + + + + +
def VelocityControl.VelocityControllerNode.odometry_callback ( self,
 msg 
)
+
+
Handle updated measured velocity callback.
+
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController-members.html b/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController-members.html new file mode 100644 index 0000000..06d2b53 --- /dev/null +++ b/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController-members.html @@ -0,0 +1,93 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
cascaded_pid_dp_controller.ROV_CascadedController Member List
+
+
+ +

This is the complete list of members for cascaded_pid_dp_controller.ROV_CascadedController, including all inherited members.

+ + + + + + + + + + + +
__init__(self) (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
cmd_pose_pub (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
o_callback(self, msg) (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
odom_pos (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
odom_quat (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
odom_vel_ang (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
odom_vel_lin (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
saturate(self) (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
sub_odometry (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
update_controller(self) (defined in cascaded_pid_dp_controller.ROV_CascadedController)cascaded_pid_dp_controller.ROV_CascadedController
+ + + + diff --git a/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController.html b/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController.html new file mode 100644 index 0000000..d190c7c --- /dev/null +++ b/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController.html @@ -0,0 +1,130 @@ + + + + + + + +Anahita: cascaded_pid_dp_controller.ROV_CascadedController Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
cascaded_pid_dp_controller.ROV_CascadedController Class Reference
+
+
+
+Inheritance diagram for cascaded_pid_dp_controller.ROV_CascadedController:
+
+
+ +
+ + + + + + + + + + +

+Public Member Functions

+def __init__ (self)
 
+def update_controller (self)
 
+def saturate (self)
 
+def o_callback (self, msg)
 
+ + + + + + + + + + + + + +

+Public Attributes

odom_pos
 
odom_quat
 
odom_vel_ang
 
odom_vel_lin
 
sub_odometry
 
cmd_pose_pub
 
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController.png b/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController.png new file mode 100644 index 0000000..0818495 Binary files /dev/null and b/docs/html/classcascaded__pid__dp__controller_1_1ROV__CascadedController.png differ diff --git a/docs/html/classcolor__correction.html b/docs/html/classcolor__correction.html new file mode 100644 index 0000000..b5ae852 --- /dev/null +++ b/docs/html/classcolor__correction.html @@ -0,0 +1,103 @@ + + + + + + + +Anahita: color_correction Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Classes
+
+
color_correction Class Reference
+
+
+ +

class defining generic interfaces and methods common for color correction methods + More...

+ +

#include <color_constancy.hpp>

+ + + + + + + + + + + + + +

+Classes

class  contrast_stretching
 class defining methods to perform color correction using modified contrast stretching More...
 
class  gray_edge
 
class  gray_world
 
class  max_edge
 
class  maxRGB
 
+

Detailed Description

+

class defining generic interfaces and methods common for color correction methods

+

The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classcolor__correction_1_1contrast__stretching-members.html b/docs/html/classcolor__correction_1_1contrast__stretching-members.html new file mode 100644 index 0000000..8309e22 --- /dev/null +++ b/docs/html/classcolor__correction_1_1contrast__stretching-members.html @@ -0,0 +1,85 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
color_correction::contrast_stretching Member List
+
+
+ +

This is the complete list of members for color_correction::contrast_stretching, including all inherited members.

+ + + +
run(Mat)color_correction::contrast_stretching
run1(Mat src)color_correction::contrast_stretching
+ + + + diff --git a/docs/html/classcolor__correction_1_1contrast__stretching.html b/docs/html/classcolor__correction_1_1contrast__stretching.html new file mode 100644 index 0000000..f4cccbb --- /dev/null +++ b/docs/html/classcolor__correction_1_1contrast__stretching.html @@ -0,0 +1,142 @@ + + + + + + + +Anahita: color_correction::contrast_stretching Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
color_correction::contrast_stretching Class Reference
+
+
+ +

class defining methods to perform color correction using modified contrast stretching + More...

+ +

#include <color_constancy.hpp>

+ + + + + + +

+Public Member Functions

Mat run (Mat)
 
Mat run1 (Mat src)
 
+

Detailed Description

+

class defining methods to perform color correction using modified contrast stretching

+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + + + + +
Mat color_correction::contrast_stretching::run (Mat src)
+
+

The main method called to perform color correction using modified contrast stretching The only input required is the input image The method computes the lower and higher threshold pixel values and then calls the contrast_stretching method

+ +
+
+ +

◆ run1()

+ +
+
+ + + + + + + + +
Mat color_correction::contrast_stretching::run1 (Mat src)
+
+

Establish the number of bins

+

Set the ranges ( for B,G,R) )

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classcolor__correction_1_1gray__edge-members.html b/docs/html/classcolor__correction_1_1gray__edge-members.html new file mode 100644 index 0000000..022de87 --- /dev/null +++ b/docs/html/classcolor__correction_1_1gray__edge-members.html @@ -0,0 +1,84 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
color_correction::gray_edge Member List
+
+
+ +

This is the complete list of members for color_correction::gray_edge, including all inherited members.

+ + +
run(Mat, int p, int m)color_correction::gray_edge
+ + + + diff --git a/docs/html/classcolor__correction_1_1gray__edge.html b/docs/html/classcolor__correction_1_1gray__edge.html new file mode 100644 index 0000000..46a36c2 --- /dev/null +++ b/docs/html/classcolor__correction_1_1gray__edge.html @@ -0,0 +1,129 @@ + + + + + + + +Anahita: color_correction::gray_edge Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
color_correction::gray_edge Class Reference
+
+
+ + + + +

+Public Member Functions

Mat run (Mat, int p, int m)
 
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Mat color_correction::gray_edge::run (Mat src1,
int p,
int m 
)
+
+

this is a main function to call to perform color correction using gray edge algorithm in RGB color space

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classcolor__correction_1_1gray__world-members.html b/docs/html/classcolor__correction_1_1gray__world-members.html new file mode 100644 index 0000000..fef6a07 --- /dev/null +++ b/docs/html/classcolor__correction_1_1gray__world-members.html @@ -0,0 +1,87 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
color_correction::gray_world Member List
+
+
+ +

This is the complete list of members for color_correction::gray_world, including all inherited members.

+ + + + + +
process(Mat src1, int p, float *ml, float *ma, float *mb)color_correction::gray_world
process(Mat src1, float *ml, float *ma, float *mb, int p, int m)color_correction::gray_world
run1(Mat, int p)color_correction::gray_world
run2(Mat, int p, int m)color_correction::gray_world
+ + + + diff --git a/docs/html/classcolor__correction_1_1gray__world.html b/docs/html/classcolor__correction_1_1gray__world.html new file mode 100644 index 0000000..be9cb4c --- /dev/null +++ b/docs/html/classcolor__correction_1_1gray__world.html @@ -0,0 +1,268 @@ + + + + + + + +Anahita: color_correction::gray_world Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
color_correction::gray_world Class Reference
+
+
+ +

#include <color_constancy.hpp>

+ + + + + + + + + + +

+Public Member Functions

void process (Mat src1, int p, float *ml, float *ma, float *mb)
 
void process (Mat src1, float *ml, float *ma, float *mb, int p, int m)
 
Mat run2 (Mat, int p, int m)
 
Mat run1 (Mat, int p)
 
+

Detailed Description

+

class containing methods to perform gray world and shades of gray color correction in RGB and Lab Color space

+

Member Function Documentation

+ +

◆ process() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void color_correction::gray_world::process (Mat src1,
float * ml,
float * ma,
float * mb,
int p,
int m 
)
+
+

function to estimate the illumination vector or scaling factor for RGB color space computation inputs are the sourc image, minkownski norm factor (p), and three normalization defined by (m = 0, 1, 2) the outputs are the factor ml,ma,mb for each of the color channel

+ +
+
+ +

◆ process() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void color_correction::gray_world::process (Mat src1,
int p,
float * ml,
float * ma,
float * mb 
)
+
+

The method to compute the estimate of illumination vector. Inputs are image and norm and outputs are ml, ma, mb the estimate of illumination vector/scaling factors

+ +
+
+ +

◆ run1()

+ +
+
+ + + + + + + + + + + + + + + + + + +
Mat color_correction::gray_world::run1 (Mat src,
int p 
)
+
+

This is the main method which to call for color correction in Lab Color space.This performs basic pre-processing and calls the gray world function

+ +
+
+ +

◆ run2()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Mat color_correction::gray_world::run2 (Mat src,
int p,
int m 
)
+
+

this is a main function to call to perform color correction in RGB color space

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classcolor__correction_1_1maxRGB-members.html b/docs/html/classcolor__correction_1_1maxRGB-members.html new file mode 100644 index 0000000..866fd2f --- /dev/null +++ b/docs/html/classcolor__correction_1_1maxRGB-members.html @@ -0,0 +1,85 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
color_correction::maxRGB Member List
+
+
+ +

This is the complete list of members for color_correction::maxRGB, including all inherited members.

+ + + +
process(Mat src1, float *ml, float *ma, float *mb, int p, int m)color_correction::maxRGB
run(Mat, int p, int m)color_correction::maxRGB
+ + + + diff --git a/docs/html/classcolor__correction_1_1maxRGB.html b/docs/html/classcolor__correction_1_1maxRGB.html new file mode 100644 index 0000000..9b4825c --- /dev/null +++ b/docs/html/classcolor__correction_1_1maxRGB.html @@ -0,0 +1,184 @@ + + + + + + + +Anahita: color_correction::maxRGB Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
color_correction::maxRGB Class Reference
+
+
+ + + + + + +

+Public Member Functions

Mat run (Mat, int p, int m)
 
void process (Mat src1, float *ml, float *ma, float *mb, int p, int m)
 
+

Member Function Documentation

+ +

◆ process()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void color_correction::maxRGB::process (Mat src1,
float * ml,
float * ma,
float * mb,
int p,
int m 
)
+
+

function coputes the illumination estimate max RGB algorithm.The function takes input image,minkowski norm and normalization method . the output are ml,,ma,mb for each of the color channels

+ +
+
+ +

◆ run()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Mat color_correction::maxRGB::run (Mat src1,
int p,
int m 
)
+
+

main function to call for maxRGB color correction

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classcolor__correction_1_1max__edge-members.html b/docs/html/classcolor__correction_1_1max__edge-members.html new file mode 100644 index 0000000..322d144 --- /dev/null +++ b/docs/html/classcolor__correction_1_1max__edge-members.html @@ -0,0 +1,90 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
color_correction::max_edge Member List
+
+
+ +

This is the complete list of members for color_correction::max_edge, including all inherited members.

+ + + + + + + + +
conv2(const Mat &img, const Mat &kernel, ConvolutionType type, Mat &dest)color_correction::max_edge
CONVOLUTION_FULL enum value (defined in color_correction::max_edge)color_correction::max_edge
CONVOLUTION_SAME enum value (defined in color_correction::max_edge)color_correction::max_edge
CONVOLUTION_VALID enum value (defined in color_correction::max_edge)color_correction::max_edge
ConvolutionType enum namecolor_correction::max_edge
process(Mat src1, float *ml, float *ma, float *mb, int p, int m)color_correction::max_edge
run(Mat, int p, int m)color_correction::max_edge
+ + + + diff --git a/docs/html/classcolor__correction_1_1max__edge.html b/docs/html/classcolor__correction_1_1max__edge.html new file mode 100644 index 0000000..9bcbb18 --- /dev/null +++ b/docs/html/classcolor__correction_1_1max__edge.html @@ -0,0 +1,252 @@ + + + + + + + +Anahita: color_correction::max_edge Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Types | +Public Member Functions | +List of all members
+
+
color_correction::max_edge Class Reference
+
+
+ + + + +

+Public Types

enum  ConvolutionType { CONVOLUTION_FULL, +CONVOLUTION_SAME, +CONVOLUTION_VALID + }
 
+ + + + + + + +

+Public Member Functions

Mat run (Mat, int p, int m)
 
void conv2 (const Mat &img, const Mat &kernel, ConvolutionType type, Mat &dest)
 
void process (Mat src1, float *ml, float *ma, float *mb, int p, int m)
 
+

Member Enumeration Documentation

+ +

◆ ConvolutionType

+ +
+
+

defines convolution type

+ +
+
+

Member Function Documentation

+ +

◆ conv2()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void color_correction::max_edge::conv2 (const Mat & img,
const Mat & kernel,
ConvolutionType type,
Mat & dest 
)
+
+

method to perform 2D convolution

+ +
+
+ +

◆ process()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void color_correction::max_edge::process (Mat src1,
float * ml,
float * ma,
float * mb,
int p,
int m 
)
+
+

function that computes illumination vector for max_edge algorithm

+ +
+
+ +

◆ run()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Mat color_correction::max_edge::run (Mat src1,
int p,
int m 
)
+
+

main function to call to perform max-edge color correction

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/docs/html/classdisturbance__manager_1_1DisturbanceManager-members.html b/docs/html/classdisturbance__manager_1_1DisturbanceManager-members.html new file mode 100644 index 0000000..7b70955 --- /dev/null +++ b/docs/html/classdisturbance__manager_1_1DisturbanceManager-members.html @@ -0,0 +1,89 @@ + + + + + + + +Anahita: Member List + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
disturbance_manager.DisturbanceManager Member List
+
+
+ +

This is the complete list of members for disturbance_manager.DisturbanceManager, including all inherited members.

+ + + + + + + +
__init__(self) (defined in disturbance_manager.DisturbanceManager)disturbance_manager.DisturbanceManager
set_body_wrench(self, force, torque, duration, starting_time) (defined in disturbance_manager.DisturbanceManager)disturbance_manager.DisturbanceManager
set_current(self, velocity, horizontal_angle, vertical_angle) (defined in disturbance_manager.DisturbanceManager)disturbance_manager.DisturbanceManager
set_propeller_efficiency(self, thruster_id, eff) (defined in disturbance_manager.DisturbanceManager)disturbance_manager.DisturbanceManager
set_thrust_efficiency(self, thruster_id, eff) (defined in disturbance_manager.DisturbanceManager)disturbance_manager.DisturbanceManager
set_thruster_state(self, thruster_id, is_on) (defined in disturbance_manager.DisturbanceManager)disturbance_manager.DisturbanceManager
+ + + + diff --git a/docs/html/classdisturbance__manager_1_1DisturbanceManager.html b/docs/html/classdisturbance__manager_1_1DisturbanceManager.html new file mode 100644 index 0000000..c3b74aa --- /dev/null +++ b/docs/html/classdisturbance__manager_1_1DisturbanceManager.html @@ -0,0 +1,108 @@ + + + + + + + +Anahita: disturbance_manager.DisturbanceManager Class Reference + + + + + + + + + +
+
+ + + + + + +
+
Anahita +
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
disturbance_manager.DisturbanceManager Class Reference
+
+
+ + + + + + + + + + + + + + +

+Public Member Functions

+def __init__ (self)
 
+def set_current (self, velocity, horizontal_angle, vertical_angle)
 
+def set_body_wrench (self, force, torque, duration, starting_time)
 
+def set_thruster_state (self, thruster_id, is_on)
 
+def set_propeller_efficiency (self, thruster_id, eff)
 
+def set_thrust_efficiency (self, thruster_id, eff)
 
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/docs/html/classes.html b/docs/html/classes.html index 8f3481d..1a09e67 100644 --- a/docs/html/classes.html +++ b/docs/html/classes.html @@ -65,77 +65,237 @@
Class Index
-
a | b | f | g | i | l | m | o | r | s | t
+
a | b | c | d | e | f | g | h | i | l | m | n | o | p | r | s | t | u | v | w | x
- + + + + + + + + + + + + + + + + + + + + + + - + + + - + + + + - + + + + + + + + + + + + + + + + + + - - + + + - - + + + + + + + - - + + + + + + + + + + + + + + - + - - + + + + + + + - - + + - + - + + + + + + + + + + - + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + + + + + - - + + + + + + + + + + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - -
  a  
FindFrontTarget (master_layer.state_mach)   DVLNode (hardware_dvl)   Line   
  p  
+
TestTrajectoryPoint (test_trajectory_point)   
DVLstatus   LinearInterpolator (uuv_trajectory_generator.path_generator.linear_interpolator)   TestWaypoint (test_waypoint)   
AccelerationControllerNode (AccelerationControl)   
  e  
+
LineSegment (uuv_trajectory_generator.path_generator.line_segment)   PathGenerator (uuv_trajectory_generator.path_generator.path_generator)   TestWaypointSet (test_waypoint_set)   
ActuatorManager (uuv_auv_actuator_interface.actuator_manager)   LineTask (master_layer.state_mach)   PathMarker   Threshold (vision_commons)   
AnahitaThrusterManager (master_layer.anahita_thruster_manager)   EKF (mapping)    LineTask (master_layer.state_mach_gate_torpedo)   
  r  
+
PIDRegulator (PID.PIDRegulator)   Thruster (uuv_thrusters.models.thruster)   
  b  
TaskBaseClass (master_layer.state_mach)   ErrorDescriptor   LIPBInterpolator (uuv_trajectory_generator.path_generator.lipb_interpolator)   Pinger   ThrusterAllocatorNode (thruster_allocator)   
FindFrontTarget (master_layer.state_mach_gate_torpedo)   
ExtendedKalmanFilter (navigation)   
  m  
PointToBearing (image_undistort)   ThrusterCustom (uuv_thrusters.models.thruster_custom)   
Base_class   
  f  
+
PointToBearingNodelet (image_undistort)   ThrusterManager (uuv_thrusters.thruster_manager)   
BaseCameraParameters (image_undistort)   MappingNode (mapping)   PositionControllerNode (PositionControlUnderactuated)   ThrusterProportional (uuv_thrusters.models.thruster_proportional)   
Baudrates (mtdef)   Filter (vision_commons)   Marker   PositionControllerNode (PositionControl)    TooFar (master_layer.state_mach_gate_torpedo)   
AnahitaThrusterManager (master_layer.anahita_thruster_manager)   
  g  
+
BezierCurve (uuv_trajectory_generator.path_generator.bezier_curve)   FindBottomTarget (master_layer.state_mach)   MarkerDropper   
  r  
RescueMode (master_layer.state_mach_gate_torpedo)    TooFar (master_layer.state_mach)   
  b  
-
BouyTask (master_layer.state_mach_gate_torpedo)   FindBottomTarget (master_layer.state_mach_gate_torpedo)    MarkerDropperTask (master_layer.state_mach)   Torpedo   
BouyTask (master_layer.state_mach)   FindFrontTarget (master_layer.state_mach)   MarkerDropperTask (master_layer.state_mach_gate_torpedo)    RescueMode (master_layer.state_mach)    TorpedoTask (master_layer.state_mach)   
GateTask (master_layer.state_mach_gate_torpedo)   MarkerDropperTask (master_layer.state_mach_gate_torpedo)   
Buoy   FindFrontTarget (master_layer.state_mach_gate_torpedo)   color_correction::max_edge   RescueMode (master_layer.state_mach_gate_torpedo)   TorpedoTask (master_layer.state_mach_gate_torpedo)   
  c  
+
FinModel (uuv_auv_actuator_interface.fin_model)   color_correction::maxRGB   ROV_CascadedController (cascaded_pid_dp_controller)   TrajectoryGenerator (uuv_trajectory_generator.trajectory_generator)   
  g  
+
MID (mtdef)   
  s  
TorpedoTask (master_layer.state_mach_gate_torpedo)   TrajectoryMarkerPublisher (trajectory_marker_publisher)   
BouyTask (master_layer.state_mach)   GateTask (master_layer.state_mach)   
CameraParametersPair (image_undistort)   Morph (vision_commons)   TrajectoryPoint (uuv_trajectory_generator.trajectory_point)   
color_correction   Gate    MoveToXYZ (master_layer.state_mach_gate_torpedo)   SlamClient (mapping)    Transition (master_layer.state_mach)   
BouyTask (master_layer.state_mach_gate_torpedo)   
  i  
-
Contour (vision_commons)   GateTask (master_layer.state_mach_gate_torpedo)    MoveToXYZ (master_layer.state_mach)   StationKeeping (master_layer.state_mach)   SlamEKF (mapping)    Transition (master_layer.state_mach_gate_torpedo)   
  f  
+
color_correction::contrast_stretching   GateTask (master_layer.state_mach)   MS5837   SlamFilter (mapping)   TriangularBuoy   
Crucifix   Geometry (vision_commons)   MTDevice (mtdevice)   SlamParticle (mapping)   
  u  
  o  
+
CSInterpolator (uuv_trajectory_generator.path_generator.cs_interpolator)   Grabber   MTErrorMessage (mtdef)   SlamServer (mapping)   
  d  
+
color_correction::gray_edge   MTException (mtdef)   StartGate   Undistorter (image_undistort)   
color_correction::gray_world   MTTimeoutException (mtdef)   StationKeeping (master_layer.state_mach)   
  v  
+
DeprecatedMID (mtdef)   
  h  
+
  n  
StationKeeping (master_layer.state_mach_gate_torpedo)   
IdentifyTarget (master_layer.state_mach)   
  t  
+
Depth (image_undistort)   StereoCameraParameters (image_undistort)   Vehicle (uuv_control_interfaces.vehicle)   
DepthNodelet (image_undistort)   HelicalSegment (uuv_trajectory_generator.path_generator.helical_segment)   name   StereoInfo (image_undistort)   VelocityControllerNode (VelocityControl)   
DeviceState (mtdef)   
  i  
FindBottomTarget (master_layer.state_mach)   NavigationDevice (navigation)   StereoInfoNodelet (image_undistort)   
  w  
+
DisturbanceManager (disturbance_manager)   NavigationNode (navigation)   StereoUndistort (image_undistort)   
DPControllerBase (uuv_control_interfaces.dp_controller_base)   IdentifyTarget (master_layer.state_mach)   
  o  
+
StereoUndistortNodelet (image_undistort)   Waypoint (uuv_waypoints.waypoint)   
DPControllerLocalPlanner (uuv_control_interfaces.dp_controller_local_planner)    IdentifyTarget (master_layer.state_mach_gate_torpedo)   OctagonTask (master_layer.state_mach)   
FindBottomTarget (master_layer.state_mach_gate_torpedo)   
  l  
+
SymVehicle (uuv_control_interfaces.sym_vehicle)   WaypointSet (uuv_waypoints.waypoint_set)   
DPPIDControllerBase (uuv_control_interfaces.dp_pid_controller_base)   ImageUndistort (image_undistort)   Observation   
  t  
+
WPTrajectoryGenerator (uuv_trajectory_generator.wp_trajectory_generator)   
DubinsInterpolator (uuv_trajectory_generator.path_generator.dubins_interpolator)   ImageUndistortNodelet (image_undistort)   Octagon   
  x  
DVLData   IMUData (navigation)    OctagonTask (master_layer.state_mach_gate_torpedo)   TaskBaseClass (master_layer.state_mach)   
DvlData (navigation)   InputCameraParameters (image_undistort)   OctagonTask (master_layer.state_mach)    TaskBaseClass (master_layer.state_mach_gate_torpedo)   XDIGroup (mtdef)   
DVLEthernet   
  l  
+
OutputCameraParameters (image_undistort)   TeledyneNavigator (teledyne_navigator.driver)   XSensDriver (mtnode)   
DVLformat21_t   OutputMode (mtdef)   Test   
DVLHeader   LaplacianBlending   OutputSettings (mtdef)   TestGate   
LineTask (master_layer.state_mach)   
-
a | b | f | g | i | l | m | o | r | s | t
+
a | b | c | d | e | f | g | h | i | l | m | n | o | p | r | s | t | u | v | w | x