Commit 45cdc417 authored by Anatoly Baksheev's avatar Anatoly Baksheev

Merge pull request #13 from ozantonkal/implementing_widgets

Implementing widgets
parents e0b7e637 7e2643ab
#pragma once
#include <opencv2/viz/types.hpp>
#include <opencv2/viz/widgets.hpp>
#include <opencv2/viz/viz3d.hpp>
......@@ -35,15 +35,6 @@ namespace temp_viz
using cv::DataDepth;
using cv::DataType;
struct CV_EXPORTS ModelCoefficients
{
std::vector<float> values;
};
class CV_EXPORTS Color : public Scalar
{
public:
......@@ -81,6 +72,8 @@ namespace temp_viz
std::vector<Vertices> polygons;
};
/////////////////////////////////////////////////////////////////////////////
/// Utility functions
inline Color vtkcolor(const Color& color)
{
......@@ -90,11 +83,7 @@ namespace temp_viz
}
inline Vec3d vtkpoint(const Point3f& point) { return Vec3d(point.x, point.y, point.z); }
template<typename _Tp> inline _Tp normalized(const _Tp& v) { return v * 1/cv::norm(v); }
inline bool isNan(float x)
{
......
......@@ -10,6 +10,7 @@
#include <string>
#include <opencv2/viz/types.hpp>
#include <opencv2/viz/widgets.hpp>
#include <opencv2/viz/events.hpp>
namespace temp_viz
......@@ -25,43 +26,18 @@ namespace temp_viz
void setBackgroundColor(const Color& color = Color::black());
void addCoordinateSystem(double scale, const Affine3f& t, const String& id = "coordinate");
void showPointCloud(const String& id, InputArray cloud, InputArray colors, const Affine3f& pose = Affine3f::Identity());
void showPointCloud(const String& id, InputArray cloud, const Color& color, const Affine3f& pose = Affine3f::Identity());
bool addPointCloudNormals (const Mat &cloud, const Mat& normals, int level = 100, float scale = 0.02f, const String& id = "cloud");
void showLine(const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color = Color::white());
void showPlane(const String& id, const Vec4f& coefs, const Color& color = Color::white());
void showPlane(const String& id, const Vec4f& coefs, const Point3f& pt, const Color& color = Color::white());
void showCube(const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color = Color::white());
void showCylinder(const String& id, const Point3f& pt_on_axis, const Point3f& axis_direction, double radius, int num_sides, const Color& color = Color::white());
void showCircle(const String& id, const Point3f& pt, double radius, const Color& color = Color::white());
void showSphere(const String& id, const Point3f& pt, double radius, const Color& color = Color::white());
void showArrow(const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color = Color::white());
Affine3f getShapePose(const String& id);
void setShapePose(const String& id, const Affine3f &pose);
bool addPlane (const ModelCoefficients &coefficients, const String& id = "plane");
bool addPlane (const ModelCoefficients &coefficients, double x, double y, double z, const String& id = "plane");
bool removeCoordinateSystem (const String& id = "coordinate");
bool addPolygonMesh (const Mesh3d& mesh, const String& id = "polygon");
bool updatePolygonMesh (const Mesh3d& mesh, const String& id = "polygon");
bool addPolylineFromPolygonMesh (const Mesh3d& mesh, const String& id = "polyline");
bool addText (const String &text, int xpos, int ypos, const Color& color, int fontsize = 10, const String& id = "");
bool addPolygon(const Mat& cloud, const Color& color, const String& id = "polygon");
bool addSphere (const Point3f &center, double radius, const Color& color, const String& id = "sphere");
void spin ();
void spinOnce (int time = 1, bool force_redraw = false);
......@@ -69,6 +45,9 @@ namespace temp_viz
void registerMouseCallback(void (*callback)(const MouseEvent&, void*), void* cookie = 0);
bool wasStopped() const;
void showWidget(const String &id, const Widget &widget);
bool removeWidget(const String &id);
private:
Viz3d(const Viz3d&);
Viz3d& operator=(const Viz3d&);
......
#pragma once
#include <opencv2/core/cvdef.h>
#include <vtkSmartPointer.h>
#include <vtkLODActor.h>
namespace temp_viz
{
class Widget;
//The class is only that depends on VTK in its interface.
//It is indended for those users who want to develop own widgets system using VTK library API.
struct CV_EXPORTS WidgetAccessor
{
static vtkSmartPointer<vtkLODActor> getActor(const Widget &widget);
};
}
#pragma once
#include <opencv2/viz/types.hpp>
namespace temp_viz
{
/////////////////////////////////////////////////////////////////////////////
/// The base class for all widgets
class CV_EXPORTS Widget
{
public:
Widget();
Widget(const Widget &other);
Widget& operator =(const Widget &other);
~Widget();
void copyTo(Widget &dst);
void setColor(const Color &color);
void setPose(const Affine3f &pose);
void updatePose(const Affine3f &pose);
Affine3f getPose() const;
private:
class Impl;
Impl* impl_;
void create();
void release();
friend struct WidgetAccessor;
};
class CV_EXPORTS LineWidget : public Widget
{
public:
LineWidget(const Point3f &pt1, const Point3f &pt2, const Color &color = Color::white());
void setLineWidth(float line_width);
float getLineWidth();
};
class CV_EXPORTS PlaneWidget : public Widget
{
public:
PlaneWidget(const Vec4f& coefs, const Color &color = Color::white());
PlaneWidget(const Vec4f& coefs, const Point3f& pt, const Color &color = Color::white());
};
class CV_EXPORTS SphereWidget : public Widget
{
public:
SphereWidget(const cv::Point3f &center, float radius, int sphere_resolution = 10, const Color &color = Color::white());
};
class CV_EXPORTS ArrowWidget : public Widget
{
public:
ArrowWidget(const Point3f& pt1, const Point3f& pt2, const Color &color = Color::white());
};
class CV_EXPORTS CircleWidget : public Widget
{
public:
CircleWidget(const Point3f& pt, double radius, const Color &color = Color::white());
};
class CV_EXPORTS CylinderWidget : public Widget
{
public:
CylinderWidget(const Point3f& pt_on_axis, const Point3f& axis_direction, double radius, int numsides = 30, const Color &color = Color::white());
};
class CV_EXPORTS CubeWidget : public Widget
{
public:
CubeWidget(const Point3f& pt_min, const Point3f& pt_max, const Color &color = Color::white());
};
class CV_EXPORTS CoordinateSystemWidget : public Widget
{
public:
CoordinateSystemWidget(double scale, const Affine3f& affine);
};
}
......@@ -153,4 +153,5 @@
#endif
#include <q/shapes.h>
#include "opencv2/viz/widget_accessor.hpp"
#include <opencv2/viz/widgets.hpp>
#pragma once
#include <opencv2/viz/types.hpp>
namespace temp_viz
{
vtkSmartPointer<vtkDataSet> createLine (const cv::Point3f& pt1, const cv::Point3f& pt2);
vtkSmartPointer<vtkDataSet> createSphere (const cv::Point3f &center, float radius, int sphere_resolution = 10);
vtkSmartPointer<vtkDataSet> createCylinder (const Point3f& pt_on_axis, const Point3f& axis_direction, double radius, int numsides = 30);
vtkSmartPointer<vtkDataSet> createPlane (const Vec4f& coefs);
vtkSmartPointer<vtkDataSet> createPlane (const Vec4f& coefs, const Point3f& pt);
vtkSmartPointer<vtkDataSet> create2DCircle (const Point3f& pt, double radius);
vtkSmartPointer<vtkDataSet> createCube(const Point3f& pt_min, const Point3f& pt_max);
vtkSmartPointer<vtkDataSet> createSphere (const Point3f& pt, double radius);
vtkSmartPointer<vtkDataSet> createArrow (const Point3f& pt1, const Point3f& pt2);
//brief Allocate a new unstructured grid smartpointer. For internal use only.
void allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata);
}
......@@ -38,41 +38,6 @@ public:
void spin ();
void spinOnce (int time = 1, bool force_redraw = false);
/** \brief Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw
*
* \param[in] scale the scale of the axes (default: 1)
* \param[in] t transformation matrix
*
* RPY Angles
* Rotate the reference frame by the angle roll about axis x
* Rotate the reference frame by the angle pitch about axis y
* Rotate the reference frame by the angle yaw about axis z
*
* Description:
* Sets the orientation of the Prop3D. Orientation is specified as
* X,Y and Z rotations in that order, but they are performed as
* RotateZ, RotateX, and finally RotateY.
*
* All axies use right hand rule. x=red axis, y=green axis, z=blue axis
* z direction is point into the screen.
* z
* \
* \
* \
* -----------> x
* |
* |
* |
* |
* |
* |
* y
*/
void addCoordinateSystem (double scale, const Affine3f& t, const String& id = "coordinate");
/** \brief Removes a previously added 3D axes (coordinate system)
*/
bool removeCoordinateSystem (const String& id = "coordinate");
bool removePointCloud (const String& id = "cloud");
inline bool removePolygonMesh (const String& id = "polygon")
{
......@@ -138,18 +103,6 @@ public:
interactor_->TerminateApp ();
}
void showLine (const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color);
void showPlane (const String& id, const cv::Vec4f &coefs, const Color& color);
void showPlane (const String& id ,const cv::Vec4f &coefs, const Point3f& pt, const Color& color);
void showCube (const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color);
void showCylinder (const String& id, const Point3f& pt_on_axis, const Point3f &axis_direction, double radius, int num_sides, const Color& color);
void showCircle (const String& id, const Point3f& pt, double radius, const Color& color);
void showSphere (const String& id, const Point3f& pt, double radius, const Color& color);
void showArrow (const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color);
Affine3f getShapePose (const String& id);
void setShapePose (const String& id, const Affine3f& pose);
bool addPolygon(const cv::Mat& cloud, const Color& color, const String& id = "polygon");
bool addArrow (const Point3f& pt1, const Point3f& pt2, const Color& color, bool display_length, const String& id = "arrow");
bool addArrow (const Point3f& pt1, const Point3f& pt2, const Color& color_line, const Color& color_text, const String& id = "arrow");
......@@ -245,6 +198,11 @@ public:
void setPosition (int x, int y);
void setSize (int xw, int yw);
void showWidget(const String &id, const Widget &widget);
bool removeWidget(const String &id);
void all_data();
private:
vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
......@@ -311,6 +269,9 @@ private:
/** \brief Internal list with actor pointers and name IDs for shapes. */
cv::Ptr<ShapeActorMap> shape_actor_map_;
/** \brief Internal list with actor pointers and name IDs for all widget actors */
cv::Ptr<WidgetActorMap> widget_actor_map_;
/** \brief Boolean that holds whether or not the camera parameters were manually initialized*/
bool camera_set_;
......
......@@ -15,8 +15,17 @@ namespace temp_viz
/** \brief Internal cell array. Used for optimizing updatePointCloud. */
vtkSmartPointer<vtkIdTypeArray> cells;
};
// TODO This will be used to contain both cloud and shape actors
struct CV_EXPORTS WidgetActor
{
vtkSmartPointer<vtkProp> actor;
vtkSmartPointer<vtkMatrix4x4> viewpoint_transformation_;
vtkSmartPointer<vtkIdTypeArray> cells;
};
typedef std::map<std::string, CloudActor> CloudActorMap;
typedef std::map<std::string, vtkSmartPointer<vtkProp> > ShapeActorMap;
typedef std::map<std::string, WidgetActor> WidgetActorMap;
}
#include <opencv2/viz/types.hpp>
//////////////////////////////////////////////////////////////////////////////////////////////////////
/// cv::Color
/// cv::viz::Color
temp_viz::Color::Color() : Scalar(0, 0, 0) {}
temp_viz::Color::Color(double gray) : Scalar(gray, gray, gray) {}
......
......@@ -17,11 +17,6 @@ void temp_viz::Viz3d::setBackgroundColor(const Color& color)
impl_->setBackgroundColor(color);
}
void temp_viz::Viz3d::addCoordinateSystem(double scale, const Affine3f& t, const String& id)
{
impl_->addCoordinateSystem(scale, t, id);
}
void temp_viz::Viz3d::showPointCloud(const String& id, InputArray cloud, InputArray colors, const Affine3f& pose)
{
impl_->showPointCloud(id, cloud, colors, pose);
......@@ -72,61 +67,6 @@ void temp_viz::Viz3d::spinOnce (int time, bool force_redraw)
impl_->spinOnce(time, force_redraw);
}
void temp_viz::Viz3d::showLine(const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color)
{
impl_->showLine(id, pt1, pt2, color);
}
void temp_viz::Viz3d::showPlane(const String& id, const Vec4f &coefs, const Color& color)
{
impl_->showPlane(id, coefs, color);
}
void temp_viz::Viz3d::showPlane(const String& id, const Vec4f &coefs, const Point3f& pt, const Color& color)
{
impl_->showPlane(id, coefs, pt, color);
}
void temp_viz::Viz3d::showCube(const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color)
{
impl_->showCube(id, pt1, pt2, color);
}
void temp_viz::Viz3d::showCylinder(const String& id, const Point3f& pt_on_axis, const Point3f &axis_direction, double radius, int num_sides, const Color& color)
{
impl_->showCylinder(id, pt_on_axis, axis_direction, radius, num_sides, color);
}
void temp_viz::Viz3d::showCircle(const String& id, const Point3f& pt, double radius, const Color& color)
{
impl_->showCircle(id, pt, radius, color);
}
void temp_viz::Viz3d::showSphere (const String& id, const Point3f& pt, double radius, const Color& color)
{
impl_->showSphere(id, pt, radius, color);
}
void temp_viz::Viz3d::showArrow (const String& id, const Point3f& pt1, const Point3f& pt2, const Color& color)
{
impl_->showArrow(id,pt1,pt2,color);
}
cv::Affine3f temp_viz::Viz3d::getShapePose(const String& id)
{
return impl_->getShapePose(id);
}
void temp_viz::Viz3d::setShapePose(const String& id, const Affine3f &pose)
{
impl_->setShapePose(id, pose);
}
bool temp_viz::Viz3d::removeCoordinateSystem (const String& id)
{
return impl_->removeCoordinateSystem(id);
}
void temp_viz::Viz3d::registerKeyboardCallback(void (*callback)(const KeyboardEvent&, void*), void* cookie)
{
impl_->registerKeyboardCallback(callback, cookie);
......@@ -139,3 +79,12 @@ void temp_viz::Viz3d::registerMouseCallback(void (*callback)(const MouseEvent&,
bool temp_viz::Viz3d::wasStopped() const { return impl_->wasStopped(); }
void temp_viz::Viz3d::showWidget(const String &id, const Widget &widget)
{
impl_->showWidget(id, widget);
}
bool temp_viz::Viz3d::removeWidget(const String &id)
{
return impl_->removeWidget(id);
}
This diff is collapsed.
#include "precomp.hpp"
#include <opencv2/calib3d.hpp>
#include <q/shapes.h>
#include <q/viz3d_impl.hpp>
#include <vtkRenderWindowInteractor.h>
......@@ -17,6 +16,7 @@ temp_viz::Viz3d::VizImpl::VizImpl (const std::string &name)
: style_ (vtkSmartPointer<temp_viz::InteractorStyle>::New ())
, cloud_actor_map_ (new CloudActorMap)
, shape_actor_map_ (new ShapeActorMap)
, widget_actor_map_ (new WidgetActorMap)
, s_lastDone_(0.0)
{
renderer_ = vtkSmartPointer<vtkRenderer>::New ();
......@@ -138,71 +138,6 @@ void temp_viz::Viz3d::VizImpl::spinOnce (int time, bool force_redraw)
}
}
/////////////////////////////////////////////////////////////////////////////////////////////
void temp_viz::Viz3d::VizImpl::addCoordinateSystem (double scale, const cv::Affine3f& affine, const std::string &id)
{
vtkSmartPointer<vtkAxes> axes = vtkSmartPointer<vtkAxes>::New ();
axes->SetOrigin (0, 0, 0);
axes->SetScaleFactor (scale);
vtkSmartPointer<vtkFloatArray> axes_colors = vtkSmartPointer<vtkFloatArray>::New ();
axes_colors->Allocate (6);
axes_colors->InsertNextValue (0.0);
axes_colors->InsertNextValue (0.0);
axes_colors->InsertNextValue (0.5);
axes_colors->InsertNextValue (0.5);
axes_colors->InsertNextValue (1.0);
axes_colors->InsertNextValue (1.0);
vtkSmartPointer<vtkPolyData> axes_data = axes->GetOutput ();
axes_data->Update ();
axes_data->GetPointData ()->SetScalars (axes_colors);
vtkSmartPointer<vtkTubeFilter> axes_tubes = vtkSmartPointer<vtkTubeFilter>::New ();
axes_tubes->SetInput (axes_data);
axes_tubes->SetRadius (axes->GetScaleFactor () / 50.0);
axes_tubes->SetNumberOfSides (6);
vtkSmartPointer<vtkPolyDataMapper> axes_mapper = vtkSmartPointer<vtkPolyDataMapper>::New ();
axes_mapper->SetScalarModeToUsePointData ();
axes_mapper->SetInput (axes_tubes->GetOutput ());
vtkSmartPointer<vtkLODActor> axes_actor = vtkSmartPointer<vtkLODActor>::New ();
axes_actor->SetMapper (axes_mapper);
cv::Vec3d t = affine.translation();
axes_actor->SetPosition (t[0], t[1], t[2]);
cv::Matx33f m = affine.rotation();
cv::Vec3f rvec;
cv::Rodrigues(m, rvec);
float r_angle = cv::norm(rvec);
rvec *= 1.f/r_angle;
axes_actor->SetOrientation(0,0,0);
axes_actor->RotateWXYZ(r_angle*180/CV_PI,rvec[0], rvec[1], rvec[2]);
renderer_->AddActor (axes_actor);
(*shape_actor_map_)[id] = axes_actor;
}
/////////////////////////////////////////////////////////////////////////////////////////////
bool temp_viz::Viz3d::VizImpl::removeCoordinateSystem (const std::string &id)
{
ShapeActorMap::iterator am_it = shape_actor_map_->find (id);
if (am_it == shape_actor_map_->end ())
return false;
// Remove it from all renderers
if (!removeActorFromRenderer(am_it->second))
return false;
shape_actor_map_->erase(am_it);
return true;
}
/////////////////////////////////////////////////////////////////////////////////////////////
bool temp_viz::Viz3d::VizImpl::removePointCloud (const std::string &id)
{
......
#include "precomp.hpp"
class temp_viz::Widget::Impl
{
public:
vtkSmartPointer<vtkLODActor> actor;
int ref_counter;
Impl() : actor(vtkSmartPointer<vtkLODActor>::New()) {}
void setColor(const Color& color)
{
Color c = vtkcolor(color);
actor->GetMapper ()->ScalarVisibilityOff ();
actor->GetProperty ()->SetColor (c.val);
actor->GetProperty ()->SetEdgeColor (c.val);
actor->GetProperty ()->SetAmbient (0.8);
actor->GetProperty ()->SetDiffuse (0.8);
actor->GetProperty ()->SetSpecular (0.8);
actor->GetProperty ()->SetLighting (0);
actor->Modified ();
}
void setPose(const Affine3f& pose)
{
vtkSmartPointer<vtkMatrix4x4> matrix = convertToVtkMatrix(pose.matrix);
actor->SetUserMatrix (matrix);
actor->Modified ();
}
void updatePose(const Affine3f& pose)
{
vtkSmartPointer<vtkMatrix4x4> matrix = actor->GetUserMatrix();
if (!matrix)
{
setPose(pose);
return ;
}
Matx44f matrix_cv = convertToMatx(matrix);
Affine3f updated_pose = pose * Affine3f(matrix_cv);
matrix = convertToVtkMatrix(updated_pose.matrix);
actor->SetUserMatrix (matrix);
actor->Modified ();
}
Affine3f getPose() const
{
vtkSmartPointer<vtkMatrix4x4> matrix = actor->GetUserMatrix();
Matx44f matrix_cv = convertToMatx(matrix);
return Affine3f(matrix_cv);
}
protected:
static vtkSmartPointer<vtkMatrix4x4> convertToVtkMatrix (const cv::Matx44f& m)
{
vtkSmartPointer<vtkMatrix4x4> vtk_matrix = vtkSmartPointer<vtkMatrix4x4>::New ();
for (int i = 0; i < 4; i++)
for (int k = 0; k < 4; k++)
vtk_matrix->SetElement(i, k, m(i, k));
return vtk_matrix;
}
static cv::Matx44f convertToMatx(const vtkSmartPointer<vtkMatrix4x4>& vtk_matrix)
{
cv::Matx44f m;
for (int i = 0; i < 4; i++)
for (int k = 0; k < 4; k++)
m(i, k) = vtk_matrix->GetElement (i, k);
return m;
}
};
///////////////////////////////////////////////////////////////////////////////////////////////
/// stream accessor implementaion
vtkSmartPointer<vtkLODActor> temp_viz::WidgetAccessor::getActor(const Widget& widget)
{
return widget.impl_->actor;
}
///////////////////////////////////////////////////////////////////////////////////////////////
/// widget implementaion
temp_viz::Widget::Widget() : impl_(0)
{
create();
}
temp_viz::Widget::Widget(const Widget& other) : impl_(other.impl_)
{
if (impl_)
CV_XADD(&impl_->ref_counter, 1);
}
temp_viz::Widget& temp_viz::Widget::operator =(const Widget &other)
{
if (this != &other)
{
release();
impl_ = other.impl_;
if (impl_)
CV_XADD(&impl_->ref_counter, 1);
}
return *this;
}
temp_viz::Widget::~Widget()
{
release();
}
void temp_viz::Widget::copyTo(Widget& /*dst*/)
{
// TODO Deep copy the data if there is any
}
void temp_viz::Widget::setColor(const Color& color) { impl_->setColor(color); }
void temp_viz::Widget::setPose(const Affine3f& pose) { impl_->setPose(pose); }
void temp_viz::Widget::updatePose(const Affine3f& pose) { impl_->updatePose(pose); }
temp_viz::Affine3f temp_viz::Widget::getPose() const { return impl_->getPose(); }
void temp_viz::Widget::create()
{
if (impl_)
release();
impl_ = new Impl();
impl_->ref_counter = 1;
}
void temp_viz::Widget::release()
{
if (impl_ && CV_XADD(&impl_->ref_counter, -1) == 1)
{
delete impl_;
}
}
......@@ -47,10 +47,9 @@
#include <fstream>
#include <string>
#include <opencv2/viz/types.hpp>
#include <opencv2/viz.hpp>
#include <opencv2/viz/mesh_load.hpp>
cv::Mat cvcloud_load()
{
cv::Mat cloud(1, 20000, CV_32FC3);
......@@ -74,8 +73,6 @@ TEST(Viz_viz3d, accuracy)
v.setBackgroundColor();
v.addCoordinateSystem(1.0, cv::Affine3f::Identity());
cv::Mat cloud = cvcloud_load();
cv::Mat colors(cloud.size(), CV_8UC3, cv::Scalar(0, 255, 0));
......@@ -92,25 +89,44 @@ TEST(Viz_viz3d, accuracy)
int col_blue = 0;
int col_green = 0;
int col_red = 0;
v.showCircle("circle1", cv::Point3f(0,0,0), 1.0, temp_viz::Color(0,255,0));
v.showSphere("sphere1", cv::Point3f(0,0,0), 0.5, temp_viz::Color(0,0,255));
v.showArrow("arrow1", cv::Point3f(0,0,0), cv::Point3f(1,1,1), temp_viz::Color(255,0,0));
temp_viz::LineWidget lw(cv::Point3f(0.0,0.0,0.0), cv::Point3f(4.0,4.0,4.0), temp_viz::Color(0,255,0));
temp_viz::PlaneWidget pw(cv::Vec4f(0.0,1.0,2.0,3.0));
temp_viz::SphereWidget sw(cv::Point3f(0,0,0), 0.5);
temp_viz::ArrowWidget aw(cv::Point3f(0,0,0), cv::Point3f(1,1,1), temp_viz::Color(255,0,0));
temp_viz::CircleWidget cw(cv::Point3f(0,0,0), 1.0, temp_viz::Color(0,255,0));
temp_viz::CylinderWidget cyw(cv::Point3f(0,0,0), cv::Point3f(-1,-1,-1), 0.5, 30, temp_viz::Color(0,255,0));
temp_viz::CubeWidget cuw(cv::Point3f(-2,-2,-2), cv::Point3f(-1,-1,-1), temp_viz::Color(0,0,255));
temp_viz::CoordinateSystemWidget csw(1.0f, cv::Affine3f::Identity());
v.showWidget("line", lw);
v.showWidget("plane", pw);
v.showWidget("sphere", sw);
v.showWidget("arrow", aw);
v.showWidget("circle", cw);
v.showWidget("cylinder", cyw);
v.showWidget("cube", cuw);
v.showWidget("coordinateSystem", csw);
temp_viz::LineWidget lw2 = lw;
while(!v.wasStopped())
{
// Creating new point cloud with id cloud1
cv::Affine3f cloudPosition(angle_x, angle_y, angle_z, cv::Vec3f(pos_x, pos_y, pos_z));
// v.showPointCloud("cloud1", cloud, temp_viz::Color(col_blue, col_green, col_red), cloudPosition);
// v.showLine("line1", cv::Point3f(0.0,0.0,0.0), cv::Point3f(pos_x, pos_y, pos_z) , temp_viz::Color(255-col_blue, 255-col_green, 255-col_red));
// v.showLine("line2", cv::Point3f(0.0,0.0,0.0), cv::Point3f(1.0f-pos_x, pos_y, pos_z) , temp_viz::Color(255-col_blue, 255-col_green, 255-col_red));
// v.showLine("line3", cv::Point3f(0.0,0.0,0.0), cv::Point3f(pos_x, 1.0f-pos_y, pos_z) , temp_viz::Color(255-col_blue, 255-col_green, 255-col_red));
// v.showLine("line4", cv::Point3f(0.0,0.0,0.0), cv::Point3f(pos_x, pos_y, 1.0f-pos_z) , temp_viz::Color(255-col_blue, 255-col_green, 255-col_red));
// v.showPlane("plane1", cv::Vec4f(pos_x*pos_y,pos_y,pos_z,pos_x+pos_y*pos_z), temp_viz::Color(255-col_blue, 255-col_green, 255-col_red));
// v.showCube("cube1", cv::Point3f(pos_x, pos_y, pos_z), cv::Point3f(pos_x+0.5, pos_y+0.5, pos_z+0.5), temp_viz::Color(255,150,50));
// v.showCylinder("cylinder1", cv::Point3f(0,0,0), cv::Point3f(pos_x, 1.0, 1.0), 0.5, 5*pos_x+3, temp_viz::Color(0,255,0));
v.setShapePose("circle1", cloudPosition);
v.setShapePose("sphere1", cloudPosition);
v.setShapePose("arrow1", cloudPosition);
lw2.setColor(temp_viz::Color(col_blue, col_green, col_red));
lw.setLineWidth(lw.getLineWidth()+pos_x * 10);
pw.setColor(temp_viz::Color(col_blue, col_green, col_red));
sw.setPose(cloudPosition);
pw.setPose(cloudPosition);
aw.setPose(cloudPosition);
cw.setPose(cloudPosition);
cyw.setPose(cloudPosition);
lw.setPose(cloudPosition);
cuw.setPose(cloudPosition);
angle_x += 0.1f;
angle_y -= 0.1f;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment