Skip to content

Commit

Permalink
rebase origin/master
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Dec 10, 2024
1 parent 68b3e94 commit dd79753
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 39 deletions.
2 changes: 1 addition & 1 deletion jsk_rviz_plugins/src/bounding_box_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ namespace jsk_rviz_plugins
coloring_property_->addOption("Value", 2);

alpha_method_property_ = new rviz::EnumProperty(
"alpha_method", "flat", "alpha method",
"alpha_method", "flat", "alpha method",
this, SLOT(updateAlphaMethod()));
alpha_method_property_->addOption("flat", 0);
alpha_method_property_->addOption("value", 1);
Expand Down
66 changes: 28 additions & 38 deletions jsk_rviz_plugins/src/bounding_box_display_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -211,27 +211,29 @@ namespace jsk_rviz_plugins
const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
{
edges_.clear();
float min_value = DBL_MAX;
float max_value = -DBL_MAX;
// filter boxes before drawing
std::vector<jsk_recognition_msgs::BoundingBox> boxes;
for (auto box : msg->boxes) {
if (!isValidBoundingBox(box)) {
for (size_t i = 0; i < msg->boxes.size(); i++) {
jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
if (isValidBoundingBox(box)) {
if (box.value < value_threshold_) {
continue;
}
boxes.push_back(box);
min_value = std::min(min_value, msg->boxes[i].value);
max_value = std::max(max_value, msg->boxes[i].value);
}
else
{
ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
box.dimensions.x, box.dimensions.y, box.dimensions.z);
}
if (box.value < value_threshold_) {
continue;
}
boxes.push_back(box);
}

// draw filtered boxes
allocateShapes(boxes.size());
float min_value = DBL_MAX;
float max_value = -DBL_MAX;
for (size_t i = 0; i < boxes.size(); i++) {
min_value = std::min(min_value, boxes[i].value);
max_value = std::max(max_value, boxes[i].value);
}
for (size_t i = 0; i < boxes.size(); i++) {
jsk_recognition_msgs::BoundingBox box = boxes[i];
ShapePtr shape = shapes_[i];
Expand Down Expand Up @@ -274,40 +276,28 @@ namespace jsk_rviz_plugins
const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
{
shapes_.clear();
float min_value = DBL_MAX;
float max_value = -DBL_MAX;
// filter boxes before drawing
std::vector<jsk_recognition_msgs::BoundingBox> boxes;
for (auto box : msg->boxes) {
if (!isValidBoundingBox(box)) {
ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
box.dimensions.x, box.dimensions.y, box.dimensions.z);
continue;
}
if (box.value < value_threshold_) {
continue;
for (size_t i = 0; i < msg->boxes.size(); i++) {
jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
if (isValidBoundingBox(box)) {
if (box.value < value_threshold_) {
continue;
}
boxes.push_back(box);
min_value = std::min(min_value, msg->boxes[i].value);
max_value = std::max(max_value, msg->boxes[i].value);
}
boxes.push_back(box);
}

// draw filtered boxes
allocateBillboardLines(boxes.size());
float min_value = DBL_MAX;
float max_value = -DBL_MAX;
for (size_t i = 0; i < boxes.size(); i++) {
min_value = std::min(min_value, boxes[i].value);
max_value = std::max(max_value, boxes[i].value);
}
for (size_t i = 0; i < boxes.size(); i++) {
jsk_recognition_msgs::BoundingBox box = boxes[i];
if (!isValidBoundingBox(box)) {
else
{
ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
box.dimensions.x, box.dimensions.y, box.dimensions.z);
}
if (box.value < value_threshold_)
{
continue;
}
}

// draw filtered boxes
allocateBillboardLines(boxes.size());
for (size_t i = 0; i < boxes.size(); i++) {
jsk_recognition_msgs::BoundingBox box = boxes[i];
Expand Down

0 comments on commit dd79753

Please sign in to comment.