#include <gtest/gtest.h>
#include <math.h>
#include <iostream>
#include <opencv2/highgui/highgui.hpp>
#include <image_geometry/pinhole_camera_model.h>
#include <ros/console.h>
#include <ros/package.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/distortion_models.h>
#include <ed/entity.h>
#include <ed/world_model.h>
#include <ed/models/model_loader.h>
#include <ed/update_request.h>
#include <ed/rendering.h>
#include <ed/uuid.h>
#include <ed/relations/transform_cache.h>
#include <geolib/Shape.h>
#include <geolib/sensors/DepthCamera.h>
#include <rgbd/image.h>
#include "tue/config/reader_writer.h"
#include "tue/config/loaders/sdf.h"
#include <ed/kinect/fitter.h>
Go to the source code of this file.
|
double | degToRad (double input) |
| degToRad converts degrees to radians More...
|
|
bool | fitSupportingEntity (const rgbd::Image *image, const geo::Pose3D &sensor_pose, const ed::WorldModel &wm, const ed::UUID &entity_id, const double max_yaw_change, const Fitter &fitter, geo::Pose3D &new_pose) |
| fitSupportingEntity fits a supporting entity More...
|
|
sensor_msgs::CameraInfo | getDefaultCamInfo (const ImageResolution &resolution) |
|
double | getYaw (const geo::Mat3 &rotation) |
|
int | main (int argc, char **argv) |
|
void | moveFurnitureObject (const ed::UUID &id, const geo::Pose3D &new_pose, ed::WorldModel &wm) |
|
void | summarizeResult (std::vector< geo::Pose3D > &succeeded_poses, std::vector< geo::Pose3D > &failed_poses) |
|
| TEST_F (FurnitureFitTest, testCase) |
|
EulerAngles | ToEulerAngles (Quaternion q) |
|
◆ degToRad()
double degToRad |
( |
double |
input | ) |
|
◆ fitSupportingEntity()
fitSupportingEntity fits a supporting entity
- Parameters
-
image | depth image |
sensor_pose | pose of the camera when the image was taken |
wm | current world model |
entity_id | id of the entity that will be fitted |
max_yaw_change | max angle change |
fitter | |
new_pose | |
- Returns
- success
Definition at line 150 of file test_furniture_fit.cpp.
◆ getDefaultCamInfo()
sensor_msgs::CameraInfo getDefaultCamInfo |
( |
const ImageResolution & |
resolution | ) |
|
◆ getYaw()
◆ main()
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ moveFurnitureObject()
◆ summarizeResult()
◆ TEST_F()
◆ ToEulerAngles()
◆ CAM_RESOLUTION_HEIGHT
const uint CAM_RESOLUTION_HEIGHT = 480 |
◆ CAM_RESOLUTION_WIDTH
const uint CAM_RESOLUTION_WIDTH = 640 |
◆ MAX_POSITION_ERROR
const double MAX_POSITION_ERROR = 0.05 |
◆ MAX_YAW_ERROR_DEGREES
const double MAX_YAW_ERROR_DEGREES = 5.0 |
◆ NR_SUCCEEDED_POSES
const uint NR_SUCCEEDED_POSES = 1089 - 106 |
◆ NR_TEST_POSES
const uint NR_TEST_POSES = 1089 |
◆ SHOW_DEBUG_IMAGES
bool SHOW_DEBUG_IMAGES = false |