ed_sensor_integration
Classes | Functions | Variables
fitter.cpp File Reference
#include <limits>
#include <ros/console.h>
#include "ed/kinect/fitter.h"
#include <ed/entity.h>
#include <ed/world_model.h>
#include <ed/update_request.h>
#include <ed/logging.h>
#include <geolib/Shape.h>
#include <rgbd/image.h>
#include <geolib/ros/tf_conversions.h>
#include <rgbd/view.h>
#include <opencv2/highgui/highgui.hpp>
#include "ed/kinect/mesh_tools.h"
#include <ed_sensor_integration_msgs/ImageBinary.h>
#include <sstream>
Include dependency graph for fitter.cpp:

Go to the source code of this file.

Classes

class  Candidate
 
class  OptimalFit
 
struct  YawRange
 

Functions

geo::Pose3D computeFittedPose (const geo::Transform2 &pose_sensor, ed::EntityConstPtr entity, const geo::Pose3D &sensor_pose_xya)
 
double computeFittingError (const std::vector< double > &test_ranges, const std::vector< double > &sensor_ranges)
 
geo::Vec2 computeShapeCenter (const Shape2D &shape2d)
 
YawRange computeYawRange (const geo::Pose3D &sensor_pose_xya, const geo::Pose3D &expected_entity_pose, const double &max_yaw_change)
 
void decomposePose (const geo::Pose3D &pose, geo::Pose3D &pose_xya, geo::Pose3D &pose_zrp)
 
Shape2D transformShape2D (const Shape2D &original_shape, const geo::Vec2 &transformation)
 
geo::Transform2 XYYawToTransform2 (const geo::Pose3D &pose)
 

Variables

const double ERROR_THRESHOLD = 1e5
 

Function Documentation

◆ computeFittedPose()

geo::Pose3D computeFittedPose ( const geo::Transform2 pose_sensor,
ed::EntityConstPtr  entity,
const geo::Pose3D sensor_pose_xya 
)

Definition at line 220 of file fitter.cpp.

◆ computeFittingError()

double computeFittingError ( const std::vector< double > &  test_ranges,
const std::vector< double > &  sensor_ranges 
)

Definition at line 182 of file fitter.cpp.

◆ computeShapeCenter()

geo::Vec2 computeShapeCenter ( const Shape2D shape2d)

Definition at line 59 of file fitter.cpp.

◆ computeYawRange()

YawRange computeYawRange ( const geo::Pose3D sensor_pose_xya,
const geo::Pose3D expected_entity_pose,
const double &  max_yaw_change 
)

Definition at line 41 of file fitter.cpp.

◆ decomposePose()

void decomposePose ( const geo::Pose3D pose,
geo::Pose3D pose_xya,
geo::Pose3D pose_zrp 
)

Definition at line 99 of file fitter.cpp.

◆ transformShape2D()

Shape2D transformShape2D ( const Shape2D original_shape,
const geo::Vec2 transformation 
)

Definition at line 84 of file fitter.cpp.

◆ XYYawToTransform2()

geo::Transform2 XYYawToTransform2 ( const geo::Pose3D pose)

Definition at line 116 of file fitter.cpp.

Variable Documentation

◆ ERROR_THRESHOLD

const double ERROR_THRESHOLD = 1e5

Definition at line 31 of file fitter.cpp.