Skip to content

Commit

Permalink
Added destructors and new params
Browse files Browse the repository at this point in the history
  • Loading branch information
tysik committed Jul 21, 2017
1 parent 3dc9b1a commit cb48d45
Show file tree
Hide file tree
Showing 19 changed files with 222 additions and 186 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ project(obstacle_detector)

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

find_package(catkin REQUIRED COMPONENTS roscpp roslaunch nodelet rviz std_msgs nav_msgs geometry_msgs sensor_msgs std_srvs tf laser_geometry message_generation)
find_package(catkin REQUIRED COMPONENTS roscpp roslaunch nodelet rviz std_msgs std_srvs geometry_msgs sensor_msgs tf laser_geometry message_generation)
find_package(Armadillo REQUIRED)
find_package(Boost 1.54.0 REQUIRED system)

Expand All @@ -13,7 +13,7 @@ generate_messages(DEPENDENCIES std_msgs geometry_msgs)
catkin_package(
INCLUDE_DIRS include
LIBRARIES scans_merger obstacle_extractor obstacle_tracker obstacle_publisher ${PROJECT_NAME}_nodelets ${PROJECT_NAME}_gui
CATKIN_DEPENDS roscpp nodelet rviz std_msgs nav_msgs geometry_msgs sensor_msgs std_srvs tf laser_geometry message_runtime
CATKIN_DEPENDS roscpp nodelet rviz std_msgs std_srvs geometry_msgs sensor_msgs tf laser_geometry message_runtime
)

include_directories(include ${catkin_INCLUDE_DIRS} ${ARMADILLO_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
Expand Down
44 changes: 22 additions & 22 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,7 @@ The package requires [Armadillo C++](http://arma.sourceforge.net) library for co
1.1 The scans_merger
1.2 The obstacle_extractor
1.3 The obstacle_tracker
1.4 The obstacle_publisher
1.5 The obstacle_recorder
1.4 The obstacle_publisher
2. The messages
3. Launch files
4. The displays
Expand All @@ -40,6 +39,8 @@ For the ease of use it is recomended to use appropriate Rviz panels provided for

This node converts two messages of type `sensor_msgs/LaserScan` from topics `front_scan` and `rear_scan` into a single laser scan of the same type, published under topic `scan` and/or a point cloud of type `sensor_msgs/PointCloud`, published under topic `pcl`. The difference between both is that the resulting laser scan divides the area into finite number of circular sectors and put one point (or actually one range value) in each section occupied by some measured points, whereas the resulting point cloud simply copies all of the points obtained from sensors.

The input laser scans are firstly rectified to incorporate the motion of the scanner in time.

-----------------------
<p align="center">
<img src="https://user-images.githubusercontent.com/1482514/27595821-0aa3519a-5b5e-11e7-9ce0-8f48db4592e4.gif" alt="Visual example of obstacle detector output"/>
Expand All @@ -48,23 +49,22 @@ This node converts two messages of type `sensor_msgs/LaserScan` from topics `fro
</p>
-----------------------

The resulting messages contain geometric data described with respect to a specific coordinate frame (e.g. `scanners_base`). Assuming that the coordinate frames attached to two laser scanners are called `front_scanner` and `rear_scanner`, both transformation from `scanners_base` frame to `front_scanner` frame and from `scanners_base` frame to `rear_scanner` frame must be provided. The node allows to artificially restrict measured points to some rectangular region around the `scanners_base` frame as well as to limit the resulting laser scan range. The points falling behind this region or ranges excluded from the limit will be discarded.
The resulting messages contain geometric data described with respect to a specific coordinate frame (e.g. `robot`). Assuming that the coordinate frames attached to two laser scanners are called `front_scanner` and `rear_scanner`, both transformation from `robot` frame to `front_scanner` frame and from `robot` frame to `rear_scanner` frame must be provided. The node allows to artificially restrict measured points to some rectangular region around the `robot` frame as well as to limit the resulting laser scan range. The points falling behind this region will be discarded.

Even if only one laser scanner is used, the node can be useful for simple data pre-processing, e.g. range restriction or recalculation of points to a different coordinate frame. The node uses the following set of local parameters:
Even if only one laser scanner is used, the node can be useful for simple data pre-processing, e.g. rectification, range restriction or recalculation of points to a different coordinate frame. The node uses the following set of local parameters:

* `~active` (`bool`, default: `true`) - active/sleep mode,
* `~publish_scan` (`bool`, default: `true`) - publish the merged laser scan message,
* `~publish_pcl` (`bool`, default: `false`) - publish the merged point cloud message,
* `~publish_scan` (`bool`, default: `false`) - publish the merged laser scan message,
* `~publish_pcl` (`bool`, default: `true`) - publish the merged point cloud message,
* `~ranges_num` (`int`, default: `1000`) - number of ranges (circular sectors) contained in the 360 deg laser scan message,
* `~min_scanner_range` (`double`, default: `0.05`) - minimal allowable range value for produced laser scan message,
* `~max_scanner_range` (`double`, default: `10.0`) - maximal allowable range value for produced laser scan message,
* `~max_x_range` (`double`, default: `10.0`) - limitation for points coordinates (points with coordinates behind these limitations will be discarded),
* `~min_x_range` (`double`, default: `-10.0`) - as above,
* `~max_y_range` (`double`, default: `10.0`) - as above,
* `~min_x_range` (`double`, default: `-10.0`) - limitation for points coordinates (points with coordinates behind these limitations will be discarded),
* `~max_x_range` (`double`, default: `10.0`) - as above,
* `~min_y_range` (`double`, default: `-10.0`) - as above,
* `~front_scan_frame_id` (`string`, default: `front_scanner`) - name of the coordinate frame attached to the front scanner,
* `~rear_scan_frame_id` (`string`, default: `rear_scanner`) - name of the coordinate frame attached to the rear scanner,
* `~target_frame_id` (`string`, default: `scanners_base`) - name of the coordinate frame used as the origin for the produced laser scan or point cloud.
* `~max_y_range` (`double`, default: `10.0`) - as above,
* `~fixed_frame_id` (`string`, default: `map`) - name of the fixed coordinate frame used for scan rectification in time (see `laser_geometry` package),
* `~target_frame_id` (`string`, default: `robot`) - name of the coordinate frame used as the origin for the produced laser scan or point cloud.

The package comes with Rviz panel for this node.

Expand Down Expand Up @@ -93,23 +93,23 @@ The input points are firstly grouped into subsets. The algorithm extracts segmen
The node is configurable with the following set of local parameters:

* `~active` (`bool`, default: `true`) - active/sleep mode,
* `~use_scan` (`bool`, default: `true`) - use laser scan messages,
* `~use_pcl` (`bool`, default: `false`) - use point cloud messages (if both scan and pcl are chosen, scans will have priority),
* `~use_scan` (`bool`, default: `false`) - use laser scan messages,
* `~use_pcl` (`bool`, default: `true`) - use point cloud messages (if both scan and pcl are chosen, scans will have priority),
* `~discard_converted_segments` (`bool`, default: `true`) - do not publish segments, from which the circles were spawned,
* `~transform_coordinates` (`bool`, default: `true`) - transform the coordinates of obstacles to a frame described with `frame_id` parameter,
* `~frame_id` (`string`, default: `map`) - name of the coordinate frame used as origin for produced obstacles (used only if `transform_coordinates` flag is set to true).

The following set of local parameters is dedicated to the algorithm itself:

* `~use_split_and_merge` (`bool`, default: `false`) - choose wether to use Iterative End Point Fit (false) or Split And Merge (true) algorithm to detect segments,
* `~use_split_and_merge` (`bool`, default: `true`) - choose wether to use Iterative End Point Fit (false) or Split And Merge (true) algorithm to detect segments,
* `~min_group_points` (`int`, default: `5`) - minimum number of points comprising a group to be further processed,
* `~max_group_distance` (`double`, default: `0.100`) - if the distance between two points is greater than this value, start a new group,
* `~distance_proportion` (`double`, default: `0.006136`) - enlarge the allowable distance between points proportionally to the range of point (use scan angle increment in radians),
* `~max_split_distance` (`double`, default: `0.070`) - if a point in group lays further from a leading line than this value, split the group,
* `~max_merge_separation` (`double`, default: `0.150`) - if distance between obstacles is smaller than this value, consider merging them,
* `~max_merge_spread` (`double`, default: `0.070`) - merge two segments if all of their extreme points lay closer to the leading line than this value,
* `~max_circle_radius` (`double`, default: `0.500`) - if a circle would have greater radius than this value, skip it,
* `~radius_enlargement` (`double`, default: `0.100`) - artificially enlarge the circles radius by this value.
* `~max_group_distance` (`double`, default: `0.1`) - if the distance between two points is greater than this value, start a new group,
* `~distance_proportion` (`double`, default: `0.00628`) - enlarge the allowable distance between points proportionally to the range of point (use scan angle increment in radians),
* `~max_split_distance` (`double`, default: `0.2`) - if a point in group lays further from a leading line than this value, split the group,
* `~max_merge_separation` (`double`, default: `0.2`) - if distance between obstacles is smaller than this value, consider merging them,
* `~max_merge_spread` (`double`, default: `0.2`) - merge two segments if all of their extreme points lay closer to the leading line than this value,
* `~max_circle_radius` (`double`, default: `0.6`) - if a circle would have greater radius than this value, skip it,
* `~radius_enlargement` (`double`, default: `0.3`) - artificially enlarge the circles radius by this value.

The package comes with Rviz panel for this node.

Expand Down
2 changes: 2 additions & 0 deletions include/obstacle_detector/obstacle_extractor.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ class ObstacleExtractor
{
public:
ObstacleExtractor(ros::NodeHandle& nh, ros::NodeHandle& nh_local);
~ObstacleExtractor();

private:
bool updateParams(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
Expand Down Expand Up @@ -96,6 +97,7 @@ class ObstacleExtractor
bool p_active_;
bool p_use_scan_;
bool p_use_pcl_;

bool p_use_split_and_merge_;
bool p_discard_converted_segments_;
bool p_transform_coordinates_;
Expand Down
1 change: 1 addition & 0 deletions include/obstacle_detector/obstacle_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ class ObstaclePublisher
{
public:
ObstaclePublisher(ros::NodeHandle &nh, ros::NodeHandle &nh_local);
~ObstaclePublisher();

private:
bool updateParams(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
Expand Down
1 change: 1 addition & 0 deletions include/obstacle_detector/obstacle_tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ namespace obstacle_detector
class ObstacleTracker {
public:
ObstacleTracker(ros::NodeHandle& nh, ros::NodeHandle& nh_local);
~ObstacleTracker();

private:
bool updateParams(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
Expand Down
5 changes: 3 additions & 2 deletions include/obstacle_detector/panels/obstacle_extractor_panel.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,15 +95,16 @@ private Q_SLOTS:
ros::ServiceClient params_cli_;

// Parameters
int p_min_group_points_;

bool p_active_;
bool p_use_scan_;
bool p_use_pcl_;

bool p_use_split_and_merge_;
bool p_discard_converted_segments_;
bool p_transform_coordinates_;

int p_min_group_points_;

double p_distance_proportion_;
double p_max_group_distance_;

Expand Down
1 change: 1 addition & 0 deletions include/obstacle_detector/scans_merger.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class ScansMerger
{
public:
ScansMerger(ros::NodeHandle& nh, ros::NodeHandle& nh_local);
~ScansMerger();

private:
bool updateParams(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
Expand Down
7 changes: 3 additions & 4 deletions launch/demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,8 @@
<param name="min_y_range" value="-10.0"/>
<param name="max_y_range" value="10.0"/>

<param name="front_scan_frame_id" value="front_scanner"/>
<param name="rear_scan_frame_id" value="rear_scanner"/>
<param name="target_frame_id" value="scanner_base"/>
<param name="fixed_frame_id" value="map"/>
<param name="target_frame_id" value="scanner_base"/>
</node>

<node pkg="nodelet" type="nodelet" name="obstacle_extractor" args="load obstacle_detector/ObstacleExtractor nodelet_manager">
Expand All @@ -46,7 +45,7 @@
<param name="distance_proportion" value="0.00628"/>
<param name="max_split_distance" value="0.07"/>
<param name="max_merge_separation" value="0.15"/>
<param name="max_merge_spread" value="0.07"/>
<param name="max_merge_spread" value="0.1"/>
<param name="max_circle_radius" value="0.5"/>
<param name="radius_enlargement" value="0.25"/>

Expand Down
61 changes: 30 additions & 31 deletions launch/nodelets.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,44 +5,43 @@
<arg name="machine" doc="Name of the machine on which the nodes should be started"/>

<node pkg="nodelet" type="nodelet" name="scans_merger" args="load obstacle_detector/ScansMerger $(arg manager)" machine="$(arg machine)">
<param name="active" value="false"/>
<param name="publish_scan" value="true"/>
<param name="publish_pcl" value="false"/>
<param name="active" value="true"/>
<param name="publish_scan" value="false"/>
<param name="publish_pcl" value="true"/>

<param name="ranges_num" value="1000"/>
<param name="ranges_num" value="1000"/>

<param name="min_scanner_range" value="0.05"/>
<param name="max_scanner_range" value="6.0"/>
<param name="min_scanner_range" value="0.05"/>
<param name="max_scanner_range" value="10.0"/>

<param name="min_x_range" value="-10.0"/>
<param name="max_x_range" value="10.0"/>
<param name="min_y_range" value="-10.0"/>
<param name="max_y_range" value="10.0"/>
<param name="min_x_range" value="-10.0"/>
<param name="max_x_range" value="10.0"/>
<param name="min_y_range" value="-10.0"/>
<param name="max_y_range" value="10.0"/>

<param name="front_scan_frame_id" value="front_scanner"/>
<param name="rear_scan_frame_id" value="rear_scanner"/>
<param name="target_frame_id" value="scanner_base"/>
<param name="fixed_frame_id" value="map"/>
<param name="target_frame_id" value="robot"/>
</node>

<node pkg="nodelet" type="nodelet" name="obstacle_extractor" args="load obstacle_detector/ObstacleExtractor $(arg manager)" machine="$(arg machine)">
<param name="active" value="false"/>
<param name="use_scan" value="true"/>
<param name="use_pcl" value="false"/>

<param name="use_split_and_merge" value="false"/>
<param name="discard_converted_segments" value="true"/>
<param name="transform_coordinates" value="true"/>

<param name="min_group_points" value="5"/>
<param name="max_group_distance" value="0.1"/>
<param name="distance_proportion" value="0.006136"/>
<param name="max_split_distance" value="0.07"/>
<param name="max_merge_separation" value="0.15"/>
<param name="max_merge_spread" value="0.07"/>
<param name="max_circle_radius" value="0.6"/>
<param name="radius_enlargement" value="0.29"/>

<param name="frame_id" value="map"/>
<param name="active" value="false"/>
<param name="use_scan" value="true"/>
<param name="use_pcl" value="false"/>
<param name="use_split_and_merge" value="false"/>
<param name="discard_converted_segments" value="true"/>
<param name="transform_coordinates" value="true"/>

<param name="min_group_points" value="5"/>

<param name="max_group_distance" value="0.1"/>
<param name="distance_proportion" value="0.00628"/>
<param name="max_split_distance" value="0.2"/>
<param name="max_merge_separation" value="0.2"/>
<param name="max_merge_spread" value="0.2"/>
<param name="max_circle_radius" value="0.6"/>
<param name="radius_enlargement" value="0.3"/>

<param name="frame_id" value="map"/>
</node>

<node pkg="nodelet" type="nodelet" name="obstacle_tracker" args="load obstacle_detector/ObstacleTracker $(arg manager)" machine="$(arg machine)">
Expand Down
25 changes: 12 additions & 13 deletions launch/nodes.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@

<node pkg="obstacle_detector" type="scans_merger_node" name="scans_merger" machine="$(arg machine)">
<param name="active" value="true"/>
<param name="publish_scan" value="true"/>
<param name="publish_pcl" value="false"/>
<param name="publish_scan" value="false"/>
<param name="publish_pcl" value="true"/>

<param name="ranges_num" value="1000"/>

Expand All @@ -18,9 +18,8 @@
<param name="min_y_range" value="-10.0"/>
<param name="max_y_range" value="10.0"/>

<param name="front_scan_frame_id" value="front_scanner"/>
<param name="rear_scan_frame_id" value="rear_scanner"/>
<param name="target_frame_id" value="scanner_base"/>
<param name="fixed_frame_id" value="map"/>
<param name="target_frame_id" value="robot"/>
</node>

<node pkg="obstacle_detector" type="obstacle_extractor_node" name="obstacle_extractor" machine="$(arg machine)">
Expand All @@ -34,14 +33,14 @@
<param name="min_group_points" value="5"/>

<param name="max_group_distance" value="0.1"/>
<param name="distance_proportion" value="0.006136"/>
<param name="max_split_distance" value="0.07"/>
<param name="max_merge_separation" value="0.15"/>
<param name="max_merge_spread" value="0.07"/>
<param name="max_circle_radius" value="0.5"/>
<param name="radius_enlargement" value="0.25"/>

<param name="frame_id" value="world"/>
<param name="distance_proportion" value="0.00628"/>
<param name="max_split_distance" value="0.2"/>
<param name="max_merge_separation" value="0.2"/>
<param name="max_merge_spread" value="0.2"/>
<param name="max_circle_radius" value="0.6"/>
<param name="radius_enlargement" value="0.3"/>

<param name="frame_id" value="map"/>
</node>

<node pkg="obstacle_detector" type="obstacle_tracker_node" name="obstacle_tracker" machine="$(arg machine)">
Expand Down
3 changes: 1 addition & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,10 @@
<depend>roslaunch</depend>
<depend>nodelet</depend>
<depend>std_msgs</depend>
<depend>nav_msgs</depend>
<depend>std_srvs</depend>
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<depend>laser_geometry</depend>
<depend>std_srvs</depend>

<export>
<rviz plugin="${prefix}/rviz_plugins.xml"/>
Expand Down
Loading

0 comments on commit cb48d45

Please sign in to comment.