Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[ROS-O] patches #113

Open
wants to merge 6 commits into
base: noetic
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 9 additions & 5 deletions face_detector/src/face_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -316,14 +316,15 @@ class FaceDetector
approximate_depth_sync_.reset(new ApproximateDepthSync(ApproximateDepthPolicy(queue_size),
image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
approximate_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
this, _1, _2, _3, _4));
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
}
else
{
exact_depth_sync_.reset(new ExactDepthSync(ExactDepthPolicy(queue_size),
image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
exact_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
this, _1, _2, _3, _4));
this, boost::placeholders::_1, boost::placeholders::_2,
boost::placeholders::_3, boost::placeholders::_4));
}
}
else
Expand All @@ -345,14 +346,15 @@ class FaceDetector
approximate_disp_sync_.reset(new ApproximateDispSync(ApproximateDispPolicy(queue_size),
image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
approximate_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
this, _1, _2, _3, _4));
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
}
else
{
exact_disp_sync_.reset(new ExactDispSync(ExactDispPolicy(queue_size),
image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
exact_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
this, _1, _2, _3, _4));
this, boost::placeholders::_1, boost::placeholders::_2,
boost::placeholders::_3, boost::placeholders::_4));
}
}

Expand Down Expand Up @@ -716,7 +718,9 @@ class FaceDetector
else
{
max_id_++;
pos.object_id = static_cast<std::ostringstream*>(&(std::ostringstream() << max_id_))->str();
std::ostringstream oss;
oss << max_id_;
pos.object_id = oss.str();
ROS_INFO_STREAM_NAMED("face_detector", "Didn't find face to match, starting new ID " << pos.object_id);
}
result_.face_positions.push_back(pos);
Expand Down
2 changes: 1 addition & 1 deletion leg_detector/include/leg_detector/laser_processor.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ struct CompareSample
{
CompareSample() {}

inline bool operator()(const Sample* a, const Sample* b)
inline bool operator()(const Sample* a, const Sample* b) const
{
return (a->index < b->index);
}
Expand Down
17 changes: 9 additions & 8 deletions leg_detector/src/leg_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -302,15 +302,13 @@ class LegDetector

if (use_seeds_)
{
people_notifier_.registerCallback(boost::bind(&LegDetector::peopleCallback, this, _1));
people_notifier_.registerCallback([this](auto msg){ peopleCallback(msg); });
people_notifier_.setTolerance(ros::Duration(0.01));
}
laser_notifier_.registerCallback(boost::bind(&LegDetector::laserCallback, this, _1));
laser_notifier_.registerCallback([this](auto scan){ laserCallback(scan); });
laser_notifier_.setTolerance(ros::Duration(0.01));

dynamic_reconfigure::Server<leg_detector::LegDetectorConfig>::CallbackType f;
f = boost::bind(&LegDetector::configure, this, _1, _2);
server_.setCallback(f);
server_.setCallback([this](auto& config, uint32_t level){ configure(config, level); });

feature_id_ = 0;
}
Expand Down Expand Up @@ -731,9 +729,12 @@ class LegDetector

memcpy(tmp_mat.data, f.data(), f.size()*sizeof(float));

float probability = 0.5 -
forest->predict(tmp_mat, cv::noArray(), cv::ml::RTrees::PREDICT_SUM) /
forest->getRoots().size();
cv::Mat votes;

forest->getVotes(tmp_mat, votes, 0);
// first row of columns cotains class labels. Here -1 and 1.
// second row then contains the number of trees voting for this class.
float probability = static_cast<float>(votes.at<int>(1, 1)) / static_cast<float>(forest->getRoots().size());

tf::Stamped<tf::Point> loc((*i)->center(), scan->header.stamp, scan->header.frame_id);
try
Expand Down
6 changes: 3 additions & 3 deletions people_velocity_tracker/scripts/tracker.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,9 +123,9 @@ def spin(self):
while not rospy.is_shutdown():
# Remove People Older Than timeout param
now = rospy.Time.now()
for p in self.people.values():
for p in list(self.people.values()):
if now - p.age() > self.TIMEOUT:
del self.people[p.id()]
del self.people[p.get_id()]
self.publish()
rate.sleep()

Expand All @@ -134,7 +134,7 @@ def publish(self):
pl = People()
pl.header.frame_id = None

for p in self.people.values():
for p in list(self.people.values()):
p.publish_markers(self.mpub)
frame, person = p.get_person()
pl.header.frame_id = frame
Expand Down