Skip to content

Commit 0fde9ad

Browse files
new node birth
1 parent b98cc9c commit 0fde9ad

File tree

2 files changed

+87
-0
lines changed

2 files changed

+87
-0
lines changed
Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
#include "eod_node.h"
2+
3+
4+
EOD_ROS::EOD_ROS(ros::NodeHandle nh){
5+
nh_ = nh;
6+
7+
rgb_it_ = new image_transport::ImageTransport(nh_);
8+
9+
sub_rgb_.subscribe(*rgb_it_, "camera/image_raw", 1);
10+
11+
nh_p_.param("subscribe_depth", subscribe_depth, false);
12+
13+
if( !subscribe_depth){
14+
ROS_INFO("Configuring filter on rgb and info...");
15+
sub_info_.subscribe(nh_, "camera/info", 1);
16+
17+
sync_.reset( new Synchronizer(RGBInfoSyncPolicy(10), sub_rgb_, sub_info_) );
18+
sync_->registerCallback(boost::bind(&EOD_ROS::rgb_info_cb, this, boost::placeholders::_1, boost::placeholders::_2));
19+
20+
}
21+
else{
22+
image_transport::SubscriberFilter sub_depth_;
23+
24+
}
25+
message_filters::Synchronizer<RGBInfoSyncPolicy> sync(RGBInfoSyncPolicy(10), sub_rgb_, sub_info_);
26+
ROS_INFO("Configured!");
27+
}
28+
29+
void EOD_ROS::rgb_info_cb(const sensor_msgs::ImageConstPtr& image, const sensor_msgs::CameraInfoConstPtr& info){
30+
ROS_INFO("Get Image!");
31+
}
32+
33+
int main(int argc, char **argv)
34+
{
35+
ros::init(argc, argv, "extended_object_detection_node");
36+
ros::NodeHandle nh_;
37+
38+
ROS_INFO("Extended object detector started...");
39+
40+
EOD_ROS eod_ros(nh_);
41+
42+
ros::spin();
43+
44+
return 0;
45+
}
Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
/*
2+
* Extneded Object Detection ROS Node
3+
*/
4+
5+
#include <ros/ros.h>
6+
#include <cv_bridge/cv_bridge.h>
7+
#include <image_transport/image_transport.h>
8+
#include <image_transport/subscriber_filter.h>
9+
#include <message_filters/subscriber.h>
10+
#include <message_filters/synchronizer.h>
11+
#include <message_filters/sync_policies/approximate_time.h>
12+
13+
#include <sensor_msgs/Image.h>
14+
#include <sensor_msgs/CameraInfo.h>
15+
#include <sensor_msgs/image_encodings.h>
16+
17+
//#include "ObjectBase.h"
18+
19+
20+
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::CameraInfo> RGBInfoSyncPolicy;
21+
22+
typedef message_filters::Synchronizer<RGBInfoSyncPolicy> Synchronizer;
23+
24+
25+
class EOD_ROS{
26+
public:
27+
EOD_ROS(ros::NodeHandle nh);
28+
29+
void rgb_info_cb(const sensor_msgs::ImageConstPtr& image, const sensor_msgs::CameraInfoConstPtr& info);
30+
31+
private:
32+
// ros stuff
33+
ros::NodeHandle nh_, nh_p_;
34+
image_transport::ImageTransport *rgb_it_;
35+
image_transport::SubscriberFilter sub_rgb_;
36+
message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
37+
boost::shared_ptr<Synchronizer> sync_;
38+
39+
// params
40+
bool subscribe_depth;
41+
42+
};

0 commit comments

Comments
 (0)