Re: [ros-users] Problem using pcl y eigen

classic Classic list List threaded Threaded
1 message Options
Reply | Threaded
Open this post in threaded view
|

Re: [ros-users] Problem using pcl y eigen

Radu B. Rusu
Administrator
Nicolas, can you please send us the entire code (minimal example of course ;) so that we understand what doesn't work?

PS. Please keep PCL related question to this mailing list and not to ros-users@. Thank you.

Thanks,
Radu.


On 12/02/2010 07:56 AM, Nicolás Alvarez Picco wrote:

> Radu,
> When I try to compile this:
>
> int ROS_Link::samplePointsOnLine (pcl::PointXYZ p1, pcl::PointXYZ p2, double res, pcl::PointCloud<pcl::PointXYZ> &pts){
> Eigen3::Vector4f dp = p2.getVector4fMap () - p1.getVector4fMap ();
> // Compute the distance between the two points
> double dist = dp.norm ();
> dp.normalize ();
>
> Eigen3::Vector4f axis_x (1.0, 0.0, 0.0), axis_y (0.0, 1.0, 0.0), axis_z (0.0, 0.0, 1.0);
> // Compute the axis increments
> double dx = res * dp.dot (axis_x);
> double dy = res * dp.dot (axis_y);
> double dz = res * dp.dot (axis_z);
>
> int nr_pts = dist / res;
> if (nr_pts < 1)
> return (0);
>
> pts.points.resize (nr_pts);
> pts.width = nr_pts; pts.height = 1;
> for (int m = 0; m < nr_pts; ++m)
> {
> pts.points[m].x = (m + 1) * dx + p1.x;
> pts.points[m].y = (m + 1) * dy + p1.y;
> pts.points[m].z = (m + 1) * dz + p1.z;
> }
> return (nr_pts);
> }
>
> I have this error:
> from /home/robot/src/autnavarc/ros-ana-pkg/han_Planner/src/ROS_Link.cpp:1:
> /home/robot/src/ros/stacks/point_cloud_perception/eigen3/include/Eigen3/src/Core/Matrix.h: In constructor
> ‘Eigen3::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const typename
> Eigen3::ei_traits<Eigen3::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> >::Scalar&, const typename
> Eigen3::ei_traits<Eigen3::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> >::Scalar&, const typename
> Eigen3::ei_traits<Eigen3::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> >::Scalar&) [with _Scalar = float,
> int _Rows = 4, int _Cols = 1, int _Options = 0, int _MaxRows = 4, int _MaxCols = 1]’:
> /home/robot/src/autnavarc/ros-ana-pkg/han_Planner/src/ROS_Link.cpp:240: instantiated from here
> /home/robot/src/ros/stacks/point_cloud_perception/eigen3/include/Eigen3/src/Core/Matrix.h:261: error:
> ‘THIS_METHOD_IS_ONLY_FOR_VECTORS_OF_A_SPECIFIC_SIZE’ is not a member of ‘Eigen3::ei_static_assert<false>’
> make[3]: *** [CMakeFiles/LaserScanToPointCloud.dir/src/ROS_Link.o] Error 1
> make[3]: Leaving directory `/home/robot/src/autnavarc/ros-ana-pkg/han_Planner/build'
> make[2]: *** [CMakeFiles/LaserScanToPointCloud.dir/all] Error 2
> make[2]: Leaving directory `/home/robot/src/autnavarc/ros-ana-pkg/han_Planner/build'
> make[1]: *** [all] Error 2
> make[1]: Leaving directory `/home/robot/src/autnavarc/ros-ana-pkg/han_Planner/build'
>
> I don't know what is wrong with the size of the vector, any idea??
>
> Thanks
>
> Nicolas
>
>
>
> _______________________________________________
> ros-users mailing list
> [hidden email]
> https://code.ros.org/mailman/listinfo/ros-users
_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users