Go to the documentation of this file.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 #include "ros/ros.h"
00031
00032 #include <nav_msgs/GetMap.h>
00033 #include <geometry_msgs/Quaternion.h>
00034 #include <geometry_msgs/PoseStamped.h>
00035 #include <sensor_msgs/image_encodings.h>
00036 #include <image_transport/image_transport.h>
00037 #include <Eigen/Geometry>
00038 #include <HectorMapTools.h>
00039 #include <math.h>
00040 #include <tf/transform_datatypes.h>
00041
00042 using namespace std;
00043
00044
00045 double resolution = 0.05;
00046
00050 class MapAsImageProvider
00051 {
00052
00053 public:
00054
00055
00056 ros::Publisher map_publisher;
00057
00058
00059 image_transport::Subscriber image_transport_subscriber_map;
00060
00061 image_transport::ImageTransport* image_transport_;
00062
00063 ros::NodeHandle n_;
00064 ros::NodeHandle pn_;
00065
00066
00067 MapAsImageProvider()
00068 : pn_("~")
00069 {
00070
00071 image_transport_ = new image_transport::ImageTransport(n_);
00072
00073 image_transport_subscriber_map = image_transport_->subscribe("map_image_raw", 1, &MapAsImageProvider::mapCallback,this);
00074
00075 map_publisher = n_.advertise<nav_msgs::OccupancyGrid>("/map_from_jpeg", 50);
00076
00077
00078 ROS_INFO("Image to Map node started.");
00079 }
00080
00081 ~MapAsImageProvider()
00082 {
00083 delete image_transport_;
00084 }
00085
00086
00087
00088 void mapCallback(const sensor_msgs::ImageConstPtr& image)
00089 {
00090
00091 nav_msgs::OccupancyGrid map;
00092
00093 map.header.stamp = image->header.stamp;
00094 map.header.frame_id = "map";
00095 map.info.width = image->width;
00096 map.info.height = image->height;
00097 map.info.origin.orientation.w = 1;
00098 map.info.resolution = resolution;
00099 map.info.origin.position.x = -((image->width + 1) * map.info.resolution * 0.5f);
00100 map.info.origin.position.y = -((image->height + 1) * map.info.resolution * 0.5f);
00101
00102
00103 int data;
00104 for(int i=image->height -1; i>=0; i--)
00105 {
00106 for (unsigned int j=0; j<image->width;j++)
00107 {
00108 data = image->data[i*image->width + j];
00109 if(data >=123 && data <= 131){
00110 map.data.push_back(-1);
00111 }
00112 else if (data >=251 && data <= 259){
00113 map.data.push_back(0);
00114 }
00115 else
00116 map.data.push_back(100);
00117 }
00118 }
00119
00120 map_publisher.publish(map);
00121 }
00122
00123 };
00124
00125 int main(int argc, char** argv)
00126 {
00127 ros::init(argc, argv, "image_to_map_node");
00128
00129 ros::NodeHandle nh("~");
00130 nh.param("resolution", resolution, 0.05);
00131
00132
00133 MapAsImageProvider map_image_provider;
00134
00135 ros::spin();
00136
00137 return 0;
00138 }