Skip to content

Commit

Permalink
Using slg namespace for Point2D, Segment2D and polygon
Browse files Browse the repository at this point in the history
  • Loading branch information
ajtudela committed Dec 15, 2021
1 parent 91f50ac commit 4362c92
Show file tree
Hide file tree
Showing 7 changed files with 57 additions and 52 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@
Changelog for package simple_laser_geometry
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.0.0 (15-12-2021)
------------------
* Using slg namespace for Point2D, Segment2D and polygon.

2.1.0 (15-12-2021)
------------------
* Adding conversion for polygon to geometry_msgs.
Expand Down
20 changes: 10 additions & 10 deletions include/simple_laser_geometry/conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,20 +34,20 @@
typedef pcl::PointCloud<pcl::PointXYZRGB> pcloud;

namespace slg{
geometry_msgs::Point point2DToGeometryPoint(Point2D point);
Point2D geometryPointToPoint2D(geometry_msgs::Point gPoint);
geometry_msgs::Point point2DToGeometryPoint(slg::Point2D point);
slg::Point2D geometryPointToPoint2D(geometry_msgs::Point gPoint);

geometry_msgs::Pose segment2DToPose(Segment2D segment);
pcloud::Ptr segment2DToPointCloud(Segment2D segment, std_msgs::Header segHeader);
geometry_msgs::Pose segment2DToPose(slg::Segment2D segment);
pcloud::Ptr segment2DToPointCloud(slg::Segment2D segment, std_msgs::Header segHeader);

Segment2D segmentMsgToSegment2D(simple_laser_geometry::Segment segmentMsg);
simple_laser_geometry::Segment segment2DToSegmentMsg(Segment2D segment);
simple_laser_geometry::SegmentStamped segment2DToSegmentStampedMsg(std_msgs::Header header, Segment2D segment);
simple_laser_geometry::Segment segment2DToSegmentMsg(slg::Segment2D segment);
simple_laser_geometry::SegmentStamped segment2DToSegmentStampedMsg(std_msgs::Header header, slg::Segment2D segment);

std::vector<Segment2D> segmentArrayMsgToSegmentVector(simple_laser_geometry::SegmentArray segmentArrayMsg);
simple_laser_geometry::SegmentArray segmentVectorToSegmentArray(std_msgs::Header header, std::vector<Segment2D> segments);
std::vector<slg::Segment2D> segmentArrayMsgToSegmentVector(simple_laser_geometry::SegmentArray segmentArrayMsg);
simple_laser_geometry::SegmentArray segmentVectorToSegmentArray(std_msgs::Header header, std::vector<slg::Segment2D> segments);

geometry_msgs::Polygon polygonToGeometryPolygon(Polygon polygon);
Polygon geometryPolygonToPolygon(geometry_msgs::Polygon gPolygon);
geometry_msgs::Polygon polygonToGeometryPolygon(slg::Polygon polygon);
slg::Polygon geometryPolygonToPolygon(geometry_msgs::Polygon gPolygon);
}
#endif
4 changes: 3 additions & 1 deletion include/simple_laser_geometry/point2D.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#include <cmath>
#include <iostream>

namespace slg{

// Label
enum Label{BACKGROUND, PERSON};

Expand Down Expand Up @@ -65,5 +67,5 @@ struct Point2D{
double y;
Label label;
};

}
#endif
3 changes: 3 additions & 0 deletions include/simple_laser_geometry/polygon.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ const std::numeric_limits<double> DOUBLE;
const double MIN = DOUBLE.min();
const double MAX = DOUBLE.max();

namespace slg{
struct Edge{
Point2D a, b;
Edge(Point2D a = Point2D(0.0, 0.0), Point2D b = Point2D(0.0, 0.0)): a(a), b(b) {}
Expand Down Expand Up @@ -107,4 +108,6 @@ class Polygon{
std::string name;
std::vector<Edge> edges;
};
}

#endif
2 changes: 2 additions & 0 deletions include/simple_laser_geometry/segment2D.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#include "point2D.h"

namespace slg{
class Segment2D{
public:
Segment2D(){id = 0; label = BACKGROUND;}
Expand Down Expand Up @@ -144,5 +145,6 @@ class Segment2D{
std::vector<Point2D> points;
Point2D lastPointPriorSeg, firstPointNextSeg, lastCentroid;
};
}

#endif
20 changes: 7 additions & 13 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,24 +1,18 @@
<?xml version="1.0"?>
<package format="2">
<name>simple_laser_geometry</name>
<version>2.1.0</version>
<version>3.0.0</version>
<description>This package contains classes and messages to interact with laser related geometry. Useful to use with LaserScan.</description>
<maintainer email="ajtudela@gmail.com">Alberto Tudela</maintainer>
<license>MIT</license>
<author email="ajtudela@gmail.com">Alberto Tudela</author>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>roslib</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>pcl_ros</build_depend>
<depend>roscpp</depend>
<depend>roslib</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>tf</depend>
<depend>pcl_ros</depend>
<build_depend>message_generation</build_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>roslib</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>tf</exec_depend>
<exec_depend>pcl_ros</exec_depend>
<exec_depend>message_runtime</exec_depend>
</package>
56 changes: 28 additions & 28 deletions src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,20 +14,20 @@
#include "simple_laser_geometry/conversions.h"

/* Convert Point2D to geometry_msgs::Point */
geometry_msgs::Point slg::point2DToGeometryPoint(Point2D point){
geometry_msgs::Point slg::point2DToGeometryPoint(slg::Point2D point){
geometry_msgs::Point gPoint;
gPoint.x = point.x;
gPoint.y = point.y;
return gPoint;
}

/* Convert geometry_msgs::Point to Point2D */
Point2D slg::geometryPointToPoint2D(geometry_msgs::Point gPoint){
return Point2D(gPoint.x, gPoint.y);
slg::Point2D slg::geometryPointToPoint2D(geometry_msgs::Point gPoint){
return slg::Point2D(gPoint.x, gPoint.y);
}

/* Convert segment to Pose */
geometry_msgs::Pose slg::segment2DToPose(Segment2D segment){
geometry_msgs::Pose slg::segment2DToPose(slg::Segment2D segment){
// Convert segment to tf pose
tf::Pose pose;
pose.setOrigin({segment.centroid().x, segment.centroid().y, 0.0});
Expand All @@ -40,10 +40,10 @@ geometry_msgs::Pose slg::segment2DToPose(Segment2D segment){
}

/* Segment2D to PointCloud */
pcloud::Ptr slg::segment2DToPointCloud(Segment2D segment, std_msgs::Header segHeader){
pcloud::Ptr slg::segment2DToPointCloud(slg::Segment2D segment, std_msgs::Header segHeader){
pcloud::Ptr segmentCloudPtr(new pcl::PointCloud<pcl::PointXYZRGB>);

std::vector<Point2D> points = segment.getPoints();
std::vector<slg::Point2D> points = segment.getPoints();
for(auto p: points){
pcl::PointXYZRGB point;
point.x = p.x;
Expand All @@ -57,19 +57,19 @@ pcloud::Ptr slg::segment2DToPointCloud(Segment2D segment, std_msgs::Header segHe
}

/* Convert a segment message to a segment 2D */
Segment2D slg::segmentMsgToSegment2D(simple_laser_geometry::Segment segmentMsg){
Point2D lastPointPriorSeg(segmentMsg.last_point_prior_segment.x, segmentMsg.last_point_prior_segment.y);
Point2D firstPointNextSeg(segmentMsg.first_point_next_segment.x, segmentMsg.first_point_next_segment.y);
slg::Segment2D slg::segmentMsgToSegment2D(simple_laser_geometry::Segment segmentMsg){
slg::Point2D lastPointPriorSeg(segmentMsg.last_point_prior_segment.x, segmentMsg.last_point_prior_segment.y);
slg::Point2D firstPointNextSeg(segmentMsg.first_point_next_segment.x, segmentMsg.first_point_next_segment.y);

Segment2D currSegment;
slg::Segment2D currSegment;

// Read the points
for(geometry_msgs::Point point: segmentMsg.points){
currSegment.addPoint({point.x, point.y});
}

currSegment.setId(segmentMsg.id);
currSegment.setLabel((Label)segmentMsg.label);
currSegment.setLabel((slg::Label)segmentMsg.label);
currSegment.setAngularDistanceToClosestBoundary(segmentMsg.angular_distance);
currSegment.setPriorSegment(lastPointPriorSeg);
currSegment.setNextSegment(firstPointNextSeg);
Expand All @@ -78,7 +78,7 @@ Segment2D slg::segmentMsgToSegment2D(simple_laser_geometry::Segment segmentMsg){
}

/* Convert a segment 2D to a segment message */
simple_laser_geometry::Segment slg::segment2DToSegmentMsg(Segment2D segment){
simple_laser_geometry::Segment slg::segment2DToSegmentMsg(slg::Segment2D segment){
simple_laser_geometry::Segment segmentMsg;

// Transform the segment in message
Expand All @@ -90,7 +90,7 @@ simple_laser_geometry::Segment slg::segment2DToSegmentMsg(Segment2D segment){
segmentMsg.first_point_next_segment.x = segment.getNextSegment().x;
segmentMsg.first_point_next_segment.y = segment.getNextSegment().y;

for(Point2D point: segment.getPoints()){
for(slg::Point2D point: segment.getPoints()){
geometry_msgs::Point gPoint;
gPoint.x = point.x;
gPoint.y = point.y;
Expand All @@ -101,7 +101,7 @@ simple_laser_geometry::Segment slg::segment2DToSegmentMsg(Segment2D segment){
}

/* Convert a segment 2D to a segment stamped message */
simple_laser_geometry::SegmentStamped slg::segment2DToSegmentStampedMsg(std_msgs::Header header, Segment2D segment){
simple_laser_geometry::SegmentStamped slg::segment2DToSegmentStampedMsg(std_msgs::Header header, slg::Segment2D segment){
simple_laser_geometry::SegmentStamped segmentMsg;

// Header of the message
Expand All @@ -116,7 +116,7 @@ simple_laser_geometry::SegmentStamped slg::segment2DToSegmentStampedMsg(std_msgs
segmentMsg.first_point_next_segment.x = segment.getNextSegment().x;
segmentMsg.first_point_next_segment.y = segment.getNextSegment().y;

for(Point2D point: segment.getPoints()){
for(slg::Point2D point: segment.getPoints()){
geometry_msgs::Point gPoint;
gPoint.x = point.x;
gPoint.y = point.y;
Expand All @@ -127,8 +127,8 @@ simple_laser_geometry::SegmentStamped slg::segment2DToSegmentStampedMsg(std_msgs
}

/* Convert a segment array message to a vector of segments */
std::vector<Segment2D> slg::segmentArrayMsgToSegmentVector(simple_laser_geometry::SegmentArray segmentArrayMsg){
std::vector<Segment2D> segments;
std::vector<slg::Segment2D> slg::segmentArrayMsgToSegmentVector(simple_laser_geometry::SegmentArray segmentArrayMsg){
std::vector<slg::Segment2D> segments;

// Read segments
for(simple_laser_geometry::Segment segment: segmentArrayMsg.segments){
Expand All @@ -139,26 +139,26 @@ std::vector<Segment2D> slg::segmentArrayMsgToSegmentVector(simple_laser_geometry
}

/* Convert a vector of segments to a segment array message */
simple_laser_geometry::SegmentArray slg::segmentVectorToSegmentArray(std_msgs::Header header, std::vector<Segment2D> segments){
simple_laser_geometry::SegmentArray slg::segmentVectorToSegmentArray(std_msgs::Header header, std::vector<slg::Segment2D> segments){
simple_laser_geometry::SegmentArray segmentArrayMsg;

// Header of the message
segmentArrayMsg.header = header;

// Transform the segment in message
for(Segment2D segment: segments){
for(slg::Segment2D segment: segments){
segmentArrayMsg.segments.push_back(segment2DToSegmentMsg(segment));
}

return segmentArrayMsg;
}

/* Convert a polygon to a geometry polygon */
geometry_msgs::Polygon slg::polygonToGeometryPolygon(Polygon polygon){
geometry_msgs::Polygon slg::polygonToGeometryPolygon(slg::Polygon polygon){
geometry_msgs::Polygon gPolygon;

for(Edge edge: polygon.getEdges()){
Point2D p = edge.a;
for(slg::Edge edge: polygon.getEdges()){
slg::Point2D p = edge.a;
geometry_msgs::Point32 gPoint;
gPoint.x = p.x;
gPoint.y = p.y;
Expand All @@ -170,24 +170,24 @@ geometry_msgs::Polygon slg::polygonToGeometryPolygon(Polygon polygon){
}

/* Convert a geometry polygon to a polygon */
Polygon slg::geometryPolygonToPolygon(geometry_msgs::Polygon gPolygon){
Polygon polygon;
slg::Polygon slg::geometryPolygonToPolygon(geometry_msgs::Polygon gPolygon){
slg::Polygon polygon;

// Read n-1 points
for(int i = 0; i < gPolygon.points.size()-1; i++){
geometry_msgs::Point32 currPoint = gPolygon.points[i];
geometry_msgs::Point32 nextPoint = gPolygon.points[i+1];

Point2D a(currPoint.x, currPoint.y);
Point2D b(nextPoint.x, nextPoint.y);
slg::Point2D a(currPoint.x, currPoint.y);
slg::Point2D b(nextPoint.x, nextPoint.y);
polygon.addEdge({a,b});
}
// Add the last edge
geometry_msgs::Point32 firstPoint = gPolygon.points[0];
geometry_msgs::Point32 lastPoint = gPolygon.points[gPolygon.points.size()-1];

Point2D a(lastPoint.x, lastPoint.y);
Point2D b(firstPoint.x, firstPoint.y);
slg::Point2D a(lastPoint.x, lastPoint.y);
slg::Point2D b(firstPoint.x, firstPoint.y);
polygon.addEdge({a,b});

return polygon;
Expand Down

0 comments on commit 4362c92

Please sign in to comment.