00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061 #include <ros/ros.h>
00062
00063
00064 #include <sensor_msgs/LaserScan.h>
00065 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
00066
00067
00068
00069
00070 class NodeClass
00071 {
00072
00073 public:
00074 int start_left_scan, stop_left_scan, start_right_scan, stop_right_scan;
00075 int start_tray_filter, stop_tray_filter;
00076 double tray_filter_min_angle, tray_filter_max_angle;
00077 bool bFilterTray_;
00078
00079 ros::NodeHandle nodeHandle;
00080
00081 ros::Subscriber topicSub_LaserScan_raw;
00082 ros::Subscriber topicSub_Tray;
00083 ros::Publisher topicPub_LaserScan;
00084 ros::Publisher topicPub_LaserScan_self;
00085
00086 NodeClass()
00087 {
00088
00089 nodeHandle.param<int>("start_left_scan", start_left_scan, 0);
00090 nodeHandle.param<int>("stop_left_scan", stop_left_scan, 248);
00091 nodeHandle.param<int>("start_right_scan", start_right_scan, 442);
00092 nodeHandle.param<int>("stop_right_scan", stop_right_scan, 681);
00093 nodeHandle.param<int>("start_tray_filter", start_tray_filter, 442);
00094 nodeHandle.param<int>("stop_tray_filter", stop_tray_filter, 520);
00095 nodeHandle.param<double>("tray_filter_min_angle", tray_filter_min_angle, -2.941);
00096 nodeHandle.param<double>("tray_filter_max_angle", tray_filter_max_angle, -1.1431);
00097
00098 topicPub_LaserScan = nodeHandle.advertise<sensor_msgs::LaserScan>("scan_top_filtered", 1);
00099 topicPub_LaserScan_self = nodeHandle.advertise<sensor_msgs::LaserScan>("scan_top_self_filtered", 1);
00100 topicSub_LaserScan_raw = nodeHandle.subscribe("scan_top", 1, &NodeClass::scanCallback, this);
00101 topicSub_Tray = nodeHandle.subscribe("/tray_controller/state", 1, &NodeClass::trayCallback, this);
00102 bFilterTray_ = false;
00103 }
00104
00105
00106 void trayCallback(const pr2_controllers_msgs::JointTrajectoryControllerState::ConstPtr& msg)
00107 {
00108 if(msg->actual.positions[0] > tray_filter_min_angle and msg->actual.positions[0] < tray_filter_max_angle)
00109 bFilterTray_ = true;
00110 else
00111 bFilterTray_ = false;
00112 }
00113
00114 void scanCallback(const sensor_msgs::LaserScan::ConstPtr& msg)
00115 {
00116
00117 sensor_msgs::LaserScan laserScan;
00118 laserScan.header.stamp = msg->header.stamp;
00119
00120
00121 laserScan.header.frame_id = msg->header.frame_id;
00122 laserScan.angle_increment = msg->angle_increment;
00123 laserScan.range_min = msg->range_min;
00124 laserScan.range_max = msg->range_max;
00125 laserScan.time_increment = msg->time_increment;
00126
00127
00128 int num_readings = (stop_right_scan - start_left_scan);
00129 laserScan.angle_min = msg->angle_min;
00130 laserScan.angle_max = msg->angle_max;
00131 laserScan.set_ranges_size(num_readings);
00132 laserScan.set_intensities_size(0);
00133
00134 for(int i = 0; i < (stop_left_scan - start_left_scan); i++)
00135 {
00136 laserScan.ranges[i] = msg->ranges[start_left_scan + i];
00137 }
00138 for(int i = stop_left_scan+1; i < start_right_scan; i++)
00139 {
00140 laserScan.ranges[i] = 0.0;
00141 }
00142 for(int i = start_right_scan; i < stop_right_scan; i++)
00143 {
00144 laserScan.ranges[i] = msg->ranges[i];
00145 }
00146
00147 sensor_msgs::LaserScan laserScan_self;
00148 laserScan_self = laserScan;
00149 if(bFilterTray_)
00150 {
00151 for(int i = start_tray_filter; i < stop_tray_filter; i++)
00152 {
00153 laserScan_self.ranges[i] = 0.0;
00154 }
00155 }
00156
00157 topicPub_LaserScan.publish(laserScan);
00158 topicPub_LaserScan_self.publish(laserScan_self);
00159
00160 }
00161 };
00162
00163
00164
00165 int main(int argc, char** argv)
00166 {
00167
00168 ros::init(argc, argv, "hokuyo_filter");
00169
00170 NodeClass nc;
00171
00172 ros::spin();
00173 return 0;
00174 }
00175