#include <ros/ros.h>
#include <iostream>
#include <cmath>
#include <stdexcept>
#include "duration.h"
#include <sys/time.h>
#include "ros/time.h"
#include <cstdio>
#include <sstream>
#include <log4cxx/logger.h>
#include "ros/console.h"
#include <boost/static_assert.hpp>
#include <cassert>
#include <stdint.h>
#include <assert.h>
#include <stddef.h>
#include <string>
#include "ros/assert.h"
#include <vector>
#include <map>
#include <set>
#include <list>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/function.hpp>
#include "exceptions.h"
#include <boost/shared_array.hpp>
#include "ros/types.h"
#include "ros/forwards.h"
#include "ros/common.h"
#include "ros/macros.h"
#include <string.h>
#include <boost/array.hpp>
#include "serialized_message.h"
#include "message_forward.h"
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
#include "message_traits.h"
#include "ros/exception.h"
#include <boost/call_traits.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
#include <boost/bind.hpp>
#include <typeinfo>
#include <ros/message.h>
#include <boost/type_traits/is_void.hpp>
#include <boost/type_traits/is_base_of.hpp>
#include <boost/type_traits/is_const.hpp>
#include <boost/type_traits/add_const.hpp>
#include <boost/make_shared.hpp>
#include <ros/static_assert.h>
#include "ros/message_traits.h"
#include "ros/builtin_message_traits.h"
#include "ros/serialization.h"
#include "ros/message_event.h"
#include "forwards.h"
#include "timer_options.h"
#include "wall_timer_options.h"
#include "ros/service_traits.h"
#include <boost/lexical_cast.hpp>
#include "subscription_callback_helper.h"
#include "ros/spinner.h"
#include <time.h>
#include "ros/publisher.h"
#include <boost/utility.hpp>
#include "ros/service_server.h"
#include "ros/subscriber.h"
#include "ros/node_handle.h"
#include "ros/init.h"
#include "XmlRpcValue.h"
#include "node_handle.h"
#include "ros/names.h"
#include <ros/ros.h>
#include "Core"
#include "src/StlSupport/StdVector.h"
#include "src/Core/util/DisableMSVCWarnings.h"
#include "SVD"
#include "LU"
#include <limits>
#include "src/Geometry/OrthoMethods.h"
#include "src/Geometry/EulerAngles.h"
#include "src/Core/util/EnableMSVCWarnings.h"
#include <ostream>
#include <pcl/ros_macros.h>
#include <std_msgs/Header.h>
#include "ros/message_operations.h"
#include <boost/type_traits/remove_all_extents.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/mpl/assert.hpp>
#include <boost/mpl/is_sequence.hpp>
#include <boost/mpl/begin_end.hpp>
#include <boost/mpl/next_prior.hpp>
#include <boost/mpl/deref.hpp>
#include <boost/mpl/aux_/unwrap.hpp>
#include <sensor_msgs/PointField.h>
#include "pcl/point_cloud.h"
#include "pcl/ros/point_traits.h"
#include "pcl/ros/for_each_type.h"
#include "pcl/exceptions.h"
#include <boost/foreach.hpp>
#include <sensor_msgs/PointCloud2.h>
#include <boost/mpl/size.hpp>
#include <boost/ref.hpp>
#include "src/Core/util/Macros.h"
#include <cerrno>
#include <cstdlib>
#include <complex>
#include <functional>
#include <iosfwd>
#include <climits>
#include <algorithm>
#include "src/Core/util/Constants.h"
#include "src/Core/util/ForwardDeclarations.h"
#include "src/Core/util/Meta.h"
#include "src/Core/util/XprHelper.h"
#include "src/Core/util/StaticAssert.h"
#include "src/Core/util/Memory.h"
#include "src/Core/NumTraits.h"
#include "src/Core/MathFunctions.h"
#include "src/Core/GenericPacketMath.h"
#include "src/Core/arch/Default/Settings.h"
#include "src/Core/Functors.h"
#include "src/Core/DenseCoeffsBase.h"
#include "src/Core/DenseBase.h"
#include "src/Core/MatrixBase.h"
#include "src/Core/EigenBase.h"
#include "src/Core/Assign.h"
#include "src/Core/util/BlasUtil.h"
#include "src/Core/DenseStorage.h"
#include "src/Core/NestByValue.h"
#include "src/Core/ForceAlignedAccess.h"
#include "src/Core/ReturnByValue.h"
#include "src/Core/NoAlias.h"
#include "src/Core/PlainObjectBase.h"
#include "src/Core/Matrix.h"
#include "src/Core/Array.h"
#include "src/Core/CwiseBinaryOp.h"
#include "src/Core/CwiseUnaryOp.h"
#include "src/Core/CwiseNullaryOp.h"
#include "src/Core/CwiseUnaryView.h"
#include "src/Core/SelfCwiseBinaryOp.h"
#include "src/Core/Dot.h"
#include "src/Core/StableNorm.h"
#include "src/Core/MapBase.h"
#include "src/Core/Stride.h"
#include "src/Core/Map.h"
#include "src/Core/Block.h"
#include "src/Core/VectorBlock.h"
#include "src/Core/Transpose.h"
#include "src/Core/DiagonalMatrix.h"
#include "src/Core/Diagonal.h"
#include "src/Core/DiagonalProduct.h"
#include "src/Core/PermutationMatrix.h"
#include "src/Core/Transpositions.h"
#include "src/Core/Redux.h"
#include "src/Core/Visitor.h"
#include "src/Core/Fuzzy.h"
#include "src/Core/IO.h"
#include "src/Core/Swap.h"
#include "src/Core/CommaInitializer.h"
#include "src/Core/Flagged.h"
#include "src/Core/ProductBase.h"
#include "src/Core/Product.h"
#include "src/Core/TriangularMatrix.h"
#include "src/Core/SelfAdjointView.h"
#include "src/Core/SolveTriangular.h"
#include "src/Core/products/Parallelizer.h"
#include "src/Core/products/CoeffBasedProduct.h"
#include "src/Core/products/GeneralBlockPanelKernel.h"
#include "src/Core/products/GeneralMatrixVector.h"
#include "src/Core/products/GeneralMatrixMatrix.h"
#include "src/Core/products/GeneralMatrixMatrixTriangular.h"
#include "src/Core/products/SelfadjointMatrixVector.h"
#include "src/Core/products/SelfadjointMatrixMatrix.h"
#include "src/Core/products/SelfadjointProduct.h"
#include "src/Core/products/SelfadjointRank2Update.h"
#include "src/Core/products/TriangularMatrixVector.h"
#include "src/Core/products/TriangularMatrixMatrix.h"
#include "src/Core/products/TriangularSolverMatrix.h"
#include "src/Core/products/TriangularSolverVector.h"
#include "src/Core/BandMatrix.h"
#include "src/Core/BooleanRedux.h"
#include "src/Core/Select.h"
#include "src/Core/VectorwiseOp.h"
#include "src/Core/Random.h"
#include "src/Core/Replicate.h"
#include "src/Core/Reverse.h"
#include "src/Core/ArrayBase.h"
#include "src/Core/ArrayWrapper.h"
#include "src/Core/GlobalFunctions.h"
#include <bitset>
#include <boost/mpl/vector.hpp>
#include <boost/mpl/for_each.hpp>
#include <boost/preprocessor/seq/enum.hpp>
#include <boost/preprocessor/seq/for_each.hpp>
#include <boost/preprocessor/seq/transform.hpp>
#include <boost/preprocessor/cat.hpp>
#include <boost/preprocessor/repetition/repeat_from_to.hpp>
#include <boost/type_traits/is_pod.hpp>
#include <math.h>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include <Eigen/StdVector>
#include "pcl/win32_macros.h"
#include "pcl/PointIndices.h"
#include "pcl/ros/conversions.h"
#include <locale>
#include "Cholesky"
#include "QR"
#include "Geometry"
#include "Eigenvalues"
#include "geometry_msgs/Vector3.h"
Go to the source code of this file.
Classes | |
struct | Turtle |
Defines | |
#define | MAX_RUNTIME_SECONDS 0.2f |
Typedefs | |
typedef pcl::PointCloud < PointType > | PCLPointCloud |
typedef pcl::PointXYZRGB | PointType |
Functions | |
void | callback (const PCLPointCloud::ConstPtr &cloud) |
double | distBetweenTurtles (Turtle t1, Turtle t2) |
bool | FindTurtles (PointCloud *cloud, std::vector< Turtle > *turtles, double radius, double thresh) |
bool | GetCircleFromRnd2 (PointCloud *cloud, double *xzxz, double radius) |
void | GetSearchArea (PointCloud *cloud, PointCloud *cloudout, double x, double z, double radius) |
int | main (int argc, char **argv) |
Variables | |
double | ang_speed = 0.2 |
double | ang_speed_gain = 1.0 |
double | angular_vel_correction = 1.0 |
PointCloud | area |
double | base_normal [4] = {0.0} |
double | bot_radius = 0.165 |
double | bot_window_size = 0.5 |
double | cam_height = 0.55 |
PointCloud | cloudCopy |
PointCloud | cloudCut |
int | debug_draw = 0 |
PointCloud | final |
PointCloud | inliers |
double | last_normal [4] = {0.0} |
double | lin_speed = 0.3 |
double | lin_speed_var = 0.1 |
double | min_stop_dist = 0.9 |
bool | normal_initialized = false |
int | num_ransac_iter = 500 |
ros::Publisher | pub |
ros::Publisher | pubvel |
double | ransac_thresh = 0.02 |
PointCloud | slice |
double | target_dist = 1.2 |
double | targetX = 0.0 |
double | targetZ = 1.5 |
PointCloud | upright |
#define MAX_RUNTIME_SECONDS 0.2f |
Definition at line 21 of file ClearpathTurtleTrain.cpp.
typedef pcl::PointCloud<PointType> PCLPointCloud |
Definition at line 25 of file ClearpathTurtleTrain.cpp.
typedef pcl::PointXYZRGB PointType |
Definition at line 24 of file ClearpathTurtleTrain.cpp.
void callback | ( | const PCLPointCloud::ConstPtr & | cloud | ) |
Definition at line 210 of file ClearpathTurtleTrain.cpp.
Definition at line 132 of file ClearpathTurtleTrain.cpp.
bool FindTurtles | ( | PointCloud * | cloud, | |
std::vector< Turtle > * | turtles, | |||
double | radius, | |||
double | thresh | |||
) |
Definition at line 138 of file ClearpathTurtleTrain.cpp.
bool GetCircleFromRnd2 | ( | PointCloud * | cloud, | |
double * | xzxz, | |||
double | radius | |||
) |
Definition at line 87 of file ClearpathTurtleTrain.cpp.
void GetSearchArea | ( | PointCloud * | cloud, | |
PointCloud * | cloudout, | |||
double | x, | |||
double | z, | |||
double | radius | |||
) |
Definition at line 73 of file ClearpathTurtleTrain.cpp.
int main | ( | int | argc, | |
char ** | argv | |||
) |
Definition at line 373 of file ClearpathTurtleTrain.cpp.
double ang_speed = 0.2 |
Definition at line 45 of file ClearpathTurtleTrain.cpp.
double ang_speed_gain = 1.0 |
Definition at line 50 of file ClearpathTurtleTrain.cpp.
double angular_vel_correction = 1.0 |
Definition at line 42 of file ClearpathTurtleTrain.cpp.
PointCloud area |
Definition at line 67 of file ClearpathTurtleTrain.cpp.
double base_normal[4] = {0.0} |
Definition at line 56 of file ClearpathTurtleTrain.cpp.
double bot_radius = 0.165 |
Definition at line 48 of file ClearpathTurtleTrain.cpp.
double bot_window_size = 0.5 |
Definition at line 47 of file ClearpathTurtleTrain.cpp.
double cam_height = 0.55 |
Definition at line 46 of file ClearpathTurtleTrain.cpp.
PointCloud cloudCopy |
Definition at line 64 of file ClearpathTurtleTrain.cpp.
PointCloud cloudCut |
Definition at line 65 of file ClearpathTurtleTrain.cpp.
int debug_draw = 0 |
Definition at line 40 of file ClearpathTurtleTrain.cpp.
PointCloud final |
Definition at line 70 of file ClearpathTurtleTrain.cpp.
PointCloud inliers |
Definition at line 69 of file ClearpathTurtleTrain.cpp.
double last_normal[4] = {0.0} |
Definition at line 57 of file ClearpathTurtleTrain.cpp.
double lin_speed = 0.3 |
Definition at line 43 of file ClearpathTurtleTrain.cpp.
double lin_speed_var = 0.1 |
Definition at line 44 of file ClearpathTurtleTrain.cpp.
double min_stop_dist = 0.9 |
Definition at line 52 of file ClearpathTurtleTrain.cpp.
bool normal_initialized = false |
Definition at line 55 of file ClearpathTurtleTrain.cpp.
int num_ransac_iter = 500 |
Definition at line 41 of file ClearpathTurtleTrain.cpp.
ros::Publisher pub |
Definition at line 36 of file ClearpathTurtleTrain.cpp.
ros::Publisher pubvel |
Definition at line 37 of file ClearpathTurtleTrain.cpp.
double ransac_thresh = 0.02 |
Definition at line 49 of file ClearpathTurtleTrain.cpp.
PointCloud slice |
Definition at line 68 of file ClearpathTurtleTrain.cpp.
double target_dist = 1.2 |
Definition at line 51 of file ClearpathTurtleTrain.cpp.
double targetX = 0.0 |
Definition at line 60 of file ClearpathTurtleTrain.cpp.
double targetZ = 1.5 |
Definition at line 61 of file ClearpathTurtleTrain.cpp.
PointCloud upright |
Definition at line 66 of file ClearpathTurtleTrain.cpp.