Skip to content

Commit

Permalink
Renamed node to 'processing_lidar_objects'
Browse files Browse the repository at this point in the history
  • Loading branch information
MadeInPierre committed Jan 24, 2018
1 parent 87993a1 commit a1eb748
Show file tree
Hide file tree
Showing 48 changed files with 165 additions and 165 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(obstacle_detector)
project(processing_lidar_objects)

set(CMAKE_CXX_FLAGS "-std=c++11 -fpermissive ${CMAKE_CXX_FLAGS} -Wfatal-errors\ ")

Expand Down
12 changes: 6 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# The obstacle_detector package
# The processing_lidar_objects package

The `obstacle_detector` package provides utilities to detect and track obstacles from data provided by 2D laser scanners. Detected obstacles come in a form of line segments or circles. The package was designed for a robot equipped with two laser scanners therefore it contains several additional utilities. The working principles of the method are described in an article provided in the `resources` folder.
The `processing_lidar_objects` package provides utilities to detect and track obstacles from data provided by 2D laser scanners. Detected obstacles come in a form of line segments or circles. The package was designed for a robot equipped with two laser scanners therefore it contains several additional utilities. The working principles of the method are described in an article provided in the `resources` folder.

The package requires [Armadillo C++](http://arma.sourceforge.net) library for compilation and runtime.

Expand Down Expand Up @@ -126,7 +126,7 @@ The package comes with Rviz panel for this node.

### 1.3. The obstacle_tracker node

This node tracks and filters the circular obstacles with the use of Kalman filter. It subscribes to messages of custom type `obstacle_detector/Obstacles` from topic `raw_obstacles` and publishes messages of the same type under topic `tracked_obstacles`. The tracking algorithm is applied only to the circular obstacles, hence the segments list in the published message is simply a copy of the original segments. The tracked obstacles are supplemented with additional information on their velocity.
This node tracks and filters the circular obstacles with the use of Kalman filter. It subscribes to messages of custom type `processing_lidar_objects/Obstacles` from topic `raw_obstacles` and publishes messages of the same type under topic `tracked_obstacles`. The tracking algorithm is applied only to the circular obstacles, hence the segments list in the published message is simply a copy of the original segments. The tracked obstacles are supplemented with additional information on their velocity.

-----------------------
<p align="center">
Expand Down Expand Up @@ -206,12 +206,12 @@ The package provides three custom message types. All of their numerical values a
- `geometry_msgs/Point last_point` - end point of the segment.
* `Obstacles`
- `Header header`
- `obstacle_detector/SegmentObstacle[] segments`
- `obstacle_detector/CircleObstacle[] circles`
- `processing_lidar_objects/SegmentObstacle[] segments`
- `processing_lidar_objects/CircleObstacle[] circles`

## 3. The launch files

Provided launch files are good examples of how to use `obstacle_detector` package. They give a full list of parameters used by each of provided nodes.
Provided launch files are good examples of how to use `processing_lidar_objects` package. They give a full list of parameters used by each of provided nodes.
* `demo.launch` - Plays a rosbag with recorded scans and starts all of the nodes with Rviz configured with appropriate panels.
* `nodes_example.launch` - Runs all of the nodes with their parameters set to default values.
* `nodelets_example.launch` - Runs all of the nodelets with their parameters set to default values.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#pragma once

#ifndef Q_MOC_RUN
#include <obstacle_detector/Obstacles.h>
#include <processing_lidar_objects/Obstacles.h>

#include <OGRE/OgreVector3.h>
#include <OGRE/OgreSceneNode.h>
Expand All @@ -55,7 +55,7 @@ class CircleVisual

virtual ~CircleVisual();

void setData(const obstacle_detector::CircleObstacle& circle);
void setData(const processing_lidar_objects::CircleObstacle& circle);
void setFramePosition(const Ogre::Vector3& position);
void setFrameOrientation(const Ogre::Quaternion& orientation);
void setMainColor(float r, float g, float b, float a);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <OGRE/OgreSceneNode.h>
#include <OGRE/OgreSceneManager.h>

#include <obstacle_detector/Obstacles.h>
#include <processing_lidar_objects/Obstacles.h>
#include <tf/transform_listener.h>

#include <rviz/properties/color_property.h>
Expand All @@ -48,14 +48,14 @@
#include <rviz/visualization_manager.h>
#include <rviz/frame_manager.h>

#include "obstacle_detector/displays/circle_visual.h"
#include "obstacle_detector/displays/segment_visual.h"
#include "processing_lidar_objects/displays/circle_visual.h"
#include "processing_lidar_objects/displays/segment_visual.h"
#endif

namespace obstacles_display
{

class ObstaclesDisplay: public rviz::MessageFilterDisplay<obstacle_detector::Obstacles>
class ObstaclesDisplay: public rviz::MessageFilterDisplay<processing_lidar_objects::Obstacles>
{
Q_OBJECT
public:
Expand All @@ -73,7 +73,7 @@ private Q_SLOTS:
void updateThickness();

private:
void processMessage(const obstacle_detector::Obstacles::ConstPtr& obstacles_msg);
void processMessage(const processing_lidar_objects::Obstacles::ConstPtr& obstacles_msg);

std::vector< boost::shared_ptr<CircleVisual> > circle_visuals_;
std::vector< boost::shared_ptr<SegmentVisual> > segment_visuals_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#pragma once

#ifndef Q_MOC_RUN
#include <obstacle_detector/Obstacles.h>
#include <processing_lidar_objects/Obstacles.h>

#include <OGRE/OgreVector3.h>
#include <OGRE/OgreSceneNode.h>
Expand All @@ -56,7 +56,7 @@ class SegmentVisual

virtual ~SegmentVisual();

void setData(const obstacle_detector::SegmentObstacle& segment);
void setData(const processing_lidar_objects::SegmentObstacle& segment);
void setFramePosition(const Ogre::Vector3& position);
void setFrameOrientation(const Ogre::Quaternion& orientation);
void setColor(float r, float g, float b, float a);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,14 +40,14 @@
#include <std_srvs/Empty.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud.h>
#include <obstacle_detector/Obstacles.h>
#include <processing_lidar_objects/Obstacles.h>

#include "obstacle_detector/utilities/point.h"
#include "obstacle_detector/utilities/segment.h"
#include "obstacle_detector/utilities/circle.h"
#include "obstacle_detector/utilities/point_set.h"
#include "processing_lidar_objects/utilities/point.h"
#include "processing_lidar_objects/utilities/segment.h"
#include "processing_lidar_objects/utilities/circle.h"
#include "processing_lidar_objects/utilities/point_set.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

class ObstacleExtractor
Expand Down Expand Up @@ -121,4 +121,4 @@ class ObstacleExtractor
std::string p_frame_id_;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@

#include <ros/ros.h>
#include <std_srvs/Empty.h>
#include <obstacle_detector/Obstacles.h>
#include <processing_lidar_objects/Obstacles.h>

namespace obstacle_detector
namespace processing_lidar_objects
{

class ObstaclePublisher
Expand Down Expand Up @@ -67,7 +67,7 @@ class ObstaclePublisher
ros::ServiceServer params_srv_;
ros::Timer timer_;

obstacle_detector::Obstacles obstacles_;
processing_lidar_objects::Obstacles obstacles_;
double t_;

// Parameters
Expand All @@ -90,4 +90,4 @@ class ObstaclePublisher
std::string p_frame_id_;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,12 @@
#include <ros/ros.h>
#include <armadillo>
#include <std_srvs/Empty.h>
#include <obstacle_detector/Obstacles.h>
#include <processing_lidar_objects/Obstacles.h>

#include "obstacle_detector/utilities/tracked_obstacle.h"
#include "obstacle_detector/utilities/math_utilities.h"
#include "processing_lidar_objects/utilities/tracked_obstacle.h"
#include "processing_lidar_objects/utilities/math_utilities.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

class ObstacleTracker {
Expand All @@ -56,7 +56,7 @@ class ObstacleTracker {
private:
bool updateParams(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
void timerCallback(const ros::TimerEvent&);
void obstaclesCallback(const obstacle_detector::Obstacles::ConstPtr new_obstacles);
void obstaclesCallback(const processing_lidar_objects::Obstacles::ConstPtr new_obstacles);

void initialize() { std_srvs::Empty empt; updateParams(empt.request, empt.response); }

Expand Down Expand Up @@ -87,7 +87,7 @@ class ObstacleTracker {
ros::Timer timer_;

double radius_margin_;
obstacle_detector::Obstacles obstacles_;
processing_lidar_objects::Obstacles obstacles_;

std::vector<TrackedObstacle> tracked_obstacles_;
std::vector<CircleObstacle> untracked_obstacles_;
Expand All @@ -109,4 +109,4 @@ class ObstacleTracker {
std::string p_frame_id_;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
#include <QHBoxLayout>
#include <QGridLayout>

namespace obstacle_detector
namespace processing_lidar_objects
{

class ObstacleExtractorPanel : public rviz::Panel
Expand Down Expand Up @@ -119,4 +119,4 @@ private Q_SLOTS:
std::string p_frame_id_;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
#include <QListWidget>
#include <QGroupBox>

namespace obstacle_detector
namespace processing_lidar_objects
{

class ObstaclePublisherPanel : public rviz::Panel
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
#include <QHBoxLayout>
#include <QGridLayout>

namespace obstacle_detector
namespace processing_lidar_objects
{

class ObstacleTrackerPanel : public rviz::Panel
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#include <QPushButton>
#include <QLabel>

namespace obstacle_detector
namespace processing_lidar_objects
{

class ScansMergerPanel : public rviz::Panel
Expand Down Expand Up @@ -111,4 +111,4 @@ private Q_SLOTS:
std::string p_target_frame_id_;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <tf/transform_listener.h>
#include <laser_geometry/laser_geometry.h>

namespace obstacle_detector
namespace processing_lidar_objects
{

class ScansMerger
Expand Down Expand Up @@ -100,4 +100,4 @@ class ScansMerger
std::string p_target_frame_id_;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@

#pragma once

#include "obstacle_detector/utilities/point.h"
#include "obstacle_detector/utilities/segment.h"
#include "processing_lidar_objects/utilities/point.h"
#include "processing_lidar_objects/utilities/segment.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

class Circle
Expand Down Expand Up @@ -66,4 +66,4 @@ class Circle
std::vector<PointSet> point_sets;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,11 @@

#include <armadillo>

#include "obstacle_detector/utilities/point.h"
#include "obstacle_detector/utilities/segment.h"
#include "obstacle_detector/utilities/circle.h"
#include "processing_lidar_objects/utilities/point.h"
#include "processing_lidar_objects/utilities/segment.h"
#include "processing_lidar_objects/utilities/circle.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

/*
Expand Down Expand Up @@ -200,4 +200,4 @@ Circle fitCircle(const std::list<Point>& point_set)
return Circle(center, radius);
}

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Point32.h>

#include "obstacle_detector/utilities/point.h"
#include "processing_lidar_objects/utilities/point.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

inline double signum(double x) { return (x < 0.0) ? -1.0 : 1.0; }
Expand Down Expand Up @@ -98,4 +98,4 @@ inline bool checkPointInLimits(const geometry_msgs::Point32& p, double x_min, do
return true;
}

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include <cmath>
#include <iostream>

namespace obstacle_detector
namespace processing_lidar_objects
{

class Point
Expand Down Expand Up @@ -87,4 +87,4 @@ class Point
double y;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@

#include <list>

#include "obstacle_detector/utilities/point.h"
#include "processing_lidar_objects/utilities/point.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

typedef std::list<Point>::iterator PointIterator;
Expand All @@ -54,5 +54,5 @@ class PointSet
bool is_visible; // The point set is not occluded by any other point set
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects

Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,10 @@

#include <vector>

#include "obstacle_detector/utilities/point.h"
#include "obstacle_detector/utilities/point_set.h"
#include "processing_lidar_objects/utilities/point.h"
#include "processing_lidar_objects/utilities/point_set.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

class Segment
Expand Down Expand Up @@ -118,4 +118,4 @@ class Segment
std::vector<PointSet> point_sets;
};

} // namespace obstacle_detector
} // namespace processing_lidar_objects
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@

#pragma once

#include <obstacle_detector/Obstacles.h>
#include "obstacle_detector/utilities/kalman.h"
#include <processing_lidar_objects/Obstacles.h>
#include "processing_lidar_objects/utilities/kalman.h"

namespace obstacle_detector
namespace processing_lidar_objects
{

class TrackedObstacle {
Expand Down
Loading

0 comments on commit a1eb748

Please sign in to comment.