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

How to use SVM or AdaBoost to train my own data? #17

Closed
wants to merge 4 commits into from
Closed
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: 12 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,13 @@ Video:<br>
The following ros packages are required:
- pcl_ros
- <a href="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/koide3/ndt_omp">ndt_omp</a>
- <a href="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/koide3/hdl_localization">hdl_localization</a>
- <a href="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/agn-7/hdl_localization">hdl_localization</a>

## Example

Bag file (recorded in an outdoor environment):
- [hdl_400.bag.tar.gz](https://www.aisl.cs.tut.ac.jp/databases/hdl_graph_slam/hdl_400.bag.tar.gz) (933MB)
- [hdl_400.bag.tar.gz](https://www.aisl.cs.tut.ac.jp/databases/hdl_graph_slam/hdl_400.bag.tar.gz) (933MB - Moving Sensor)
- [hdl_500.bag.tar.gz](https://drive.google.com/open?id=1oPj6xJ0VpvGc_u31EQuGAqiVMnbA5Kar) (500MB - Fixed sensor)

```bash
rosparam set use_sim_time true
Expand Down Expand Up @@ -48,6 +49,15 @@ rosparam set use_sim_time true
roslaunch hdl_people_tracking hdl_people_tracking_static.launch
```

```bash
roscd hdl_localization/rviz
rviz -d hdl_localization_static.rviz
```

```bash
rosbag play --clock hdl_500.bag
```


## Related packages

Expand Down
18 changes: 12 additions & 6 deletions apps/hdl_people_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,8 +95,10 @@ class HdlPeopleDetectionNodelet : public nodelet::Nodelet {
return;
}

//iter++; // frame counter.
//std::cout<<iter<<"\n";
pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
pcl::fromROSMsg(*points_msg, *cloud);
pcl::fromROSMsg(*points_msg, *cloud); // Convert pcl2 to pcl
if(cloud->empty()) {
NODELET_ERROR("cloud is empty!!");
return;
Expand All @@ -107,11 +109,11 @@ class HdlPeopleDetectionNodelet : public nodelet::Nodelet {
downsample_filter->setInputCloud(cloud);
downsample_filter->filter(*downsampled);
downsampled->header = cloud->header;
cloud = downsampled;
//cloud = downsampled; // TODO :: aGn

// background subtraction and people detection
auto filtered = backsub->filter(cloud);
auto clusters = detector->detect(filtered);
auto filtered = backsub->filter(cloud); // preprocess
auto clusters = detector->detect(filtered); // cluster and classify

publish_msgs(points_msg->header.stamp, filtered, clusters);
}
Expand Down Expand Up @@ -139,7 +141,7 @@ class HdlPeopleDetectionNodelet : public nodelet::Nodelet {
downsample_filter->setInputCloud(cloud);
downsample_filter->filter(*downsampled);
downsampled->header = cloud->header;
cloud = downsampled;
cloud = downsampled; // TODO :: aGn

// transform #cloud into the globalmap space
const auto& position = odom_msg->pose.pose.position;
Expand Down Expand Up @@ -183,7 +185,10 @@ class HdlPeopleDetectionNodelet : public nodelet::Nodelet {
* @param filtered
* @param clusters
*/
void publish_msgs(const ros::Time& stamp, const pcl::PointCloud<pcl::PointXYZI>::Ptr& filtered, const std::vector<Cluster::Ptr>& clusters) const {
void publish_msgs(
const ros::Time& stamp,
const pcl::PointCloud<pcl::PointXYZI>::Ptr& filtered,
const std::vector<Cluster::Ptr>& clusters) const {
if(clusters_pub.getNumSubscribers()) {
hdl_people_tracking::ClusterArrayPtr clusters_msg(new hdl_people_tracking::ClusterArray());
clusters_msg->header.frame_id = globalmap->header.frame_id;
Expand Down Expand Up @@ -292,6 +297,7 @@ class HdlPeopleDetectionNodelet : public nodelet::Nodelet {
}

private:
int iter = 0;
// ROS
ros::NodeHandle nh;
ros::NodeHandle mt_nh;
Expand Down
4 changes: 2 additions & 2 deletions launch/hdl_people_tracking_static.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<param name="downsample_resolution" value="0.1"/>
<!-- back subtraction params -->
<param name="backsub_resolution" value="0.2"/>
<param name="backsub_occupancy_thresh" value="2"/>
<param name="backsub_occupancy_thresh" value="5"/>
<!-- clustering params -->
<param name="cluster_min_pts" value="10"/>
<param name="cluster_max_pts" value="2048"/>
Expand All @@ -20,7 +20,7 @@
<param name="cluster_max_size_y" value="1.0"/>
<param name="cluster_max_size_z" value="2.0"/>
<!-- classification params -->
<param name="enable_classification" value="false"/>
<param name="enable_classification" value="true"/>
</node>

<node pkg="nodelet" type="nodelet" name="hdl_people_tracking_nodelet" args="load hdl_people_tracking/HdlPeopleTrackingNodelet $(arg nodelet_manager)">
Expand Down
1 change: 1 addition & 0 deletions src/people_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ std::vector<Cluster::Ptr> PeopleDetector::detect(const pcl::PointCloud<pcl::Poin
auto clusters = marcel.detect(cloud);

for(auto& cluster : clusters) {
//std::cout<<!classifier<<"\n";
cluster->is_human = !classifier || classifier->predict(cluster->cloud);
}

Expand Down