Skip to content

Commit

Permalink
[jsk_pcl_ros_utils][polygon_magnifier] allow negative param value
Browse files Browse the repository at this point in the history
[jsk_pcl_ros_utils][polygon_magnifier] update docs
  • Loading branch information
furushchev committed Apr 17, 2017
1 parent 60a7fce commit 44a78a8
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 3 deletions.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
5 changes: 4 additions & 1 deletion doc/jsk_pcl_ros_utils/nodes/polygon_magnifier.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
# PolygonMagnifier

![](./images/polygon_magnifier.png)

Magnify polygons by specified length.

## Subscribing Topic
Expand All @@ -14,4 +17,4 @@ Magnify polygons by specified length.
## Parameters
* `~magnify_distance` (Double, default: `0.2`)

Length to scale polygon
Length to scale polygons. Default value `0.2` means the distance of each corresponding edges will be `0.2` m.
2 changes: 1 addition & 1 deletion jsk_pcl_ros_utils/cfg/PolygonMagnifier.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -9,5 +9,5 @@ from math import pi

gen = ParameterGenerator ()

gen.add("magnify_distance", double_t, 0, "Magnify distance", 0.2, 0.0, 10.0)
gen.add("magnify_distance", double_t, 0, "Magnify distance", 0.2, -10.0, 10.0)
exit (gen.generate (PACKAGE, "jsk_pcl_ros_utils", "PolygonMagnifier"))
11 changes: 10 additions & 1 deletion jsk_pcl_ros_utils/src/polygon_magnifier_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,18 @@ namespace jsk_pcl_ros_utils
{
boost::mutex::scoped_lock lock(mutex_);
vital_checker_->poke();

jsk_recognition_msgs::PolygonArray ret_polygon_array;
ret_polygon_array.header = msg->header;

ret_polygon_array.labels.reserve(msg->labels.size());
std::copy(msg->labels.begin(), msg->labels.end(),
std::back_inserter(ret_polygon_array.labels));

ret_polygon_array.likelihood.reserve(msg->likelihood.size());
std::copy(msg->likelihood.begin(), msg->likelihood.end(),
std::back_inserter(ret_polygon_array.likelihood));

for (size_t i = 0; i < msg->polygons.size(); i++) {
geometry_msgs::PolygonStamped magnified_polygon;
magnified_polygon.header = msg->polygons[i].header;
Expand All @@ -84,7 +94,6 @@ namespace jsk_pcl_ros_utils
}
pub_.publish(ret_polygon_array);
}

}

#include <pluginlib/class_list_macros.h>
Expand Down

0 comments on commit 44a78a8

Please sign in to comment.