Go to the documentation of this file.00001 #include "map_location_alg_node.h"
00002
00003 MapLocationAlgNode::MapLocationAlgNode(void) :
00004 algorithm_base::IriBaseAlgorithm<MapLocationAlgorithm>(),
00005 it_(public_node_handle_)
00006 {
00007
00008 this->loop_rate_ = 2;
00009
00010
00011 img_pub_ = it_.advertise("map_image", 1);
00012
00013
00014 this->mapcode_subscriber_ = this->public_node_handle_.subscribe("mapcode", 100, &MapLocationAlgNode::mapcode_callback, this);
00015 this->locations_subscriber_ = this->public_node_handle_.subscribe("locations", 100, &MapLocationAlgNode::locations_callback, this);
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 t=0;
00026 this->public_node_handle_.getParam("path", this->alg_.path);
00027 this->alg_.loadFiles();
00028 }
00029
00030 MapLocationAlgNode::~MapLocationAlgNode(void)
00031 {
00032
00033 }
00034
00035 void MapLocationAlgNode::mainNodeThread(void)
00036 {
00037 this->updateImage();
00038 this->updateLocations();
00039 this->alg_.mapIteration();
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049 img_pub_.publish(this->img_msg);
00050 }
00051
00052
00053 void MapLocationAlgNode::mapcode_callback(const std_msgs::String::ConstPtr& msg)
00054 {
00055 ROS_INFO("MapLocationAlgNode::mapcode_callback: New Message Received");
00056
00057
00058 this->alg_.lock();
00059
00060
00061
00062 std::string code = msg->data;
00063 this->mapCode_ = atoi(code.c_str());
00064
00065 this->alg_.addLocationWithCode(this->mapCode_);
00066
00067
00068 this->alg_.unlock();
00069
00070 }
00071 void MapLocationAlgNode::locations_callback(const geometry_msgs::PoseArray::ConstPtr& msg)
00072 {
00073 ROS_INFO("MapLocationAlgNode::locations_callback: New Message Received");
00074
00075
00076
00077 this->locations_mutex_.enter();
00078
00079
00080 this->locations = *msg;
00081
00082
00083
00084 this->locations_mutex_.exit();
00085 }
00086
00087
00088
00089
00090
00091
00092
00093 void MapLocationAlgNode::node_config_update(Config &config, uint32_t level)
00094 {
00095 this->alg_.lock();
00096
00097 this->alg_.unlock();
00098 }
00099
00100 void MapLocationAlgNode::addNodeDiagnostics(void)
00101 {
00102 }
00103
00104
00105 int main(int argc,char *argv[])
00106 {
00107 return algorithm_base::main<MapLocationAlgNode>(argc, argv, "map_location_alg_node");
00108 }
00109
00110 void MapLocationAlgNode::updateLocations()
00111 {
00112 if(this->locations.poses.size()!=0)
00113 {
00114
00115 for(unsigned int i=0; i<locations.poses.size(); i++)
00116 {
00117 this->alg_.addLocation(locations.poses[i].position.x, locations.poses[i].position.y, 0);
00118 }
00119 this->locations.poses.clear();
00120 }
00121
00122 if(t==0)
00123 this->alg_.addLocation(1050 , 900, 0);
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152 }
00153
00154 void MapLocationAlgNode::updateImage()
00155 {
00156 cv::Mat image = this->alg_.getImage();
00157 cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00158 cv_ptr->image=image;
00159 cv_ptr->encoding = "bgr8";
00160 this->img_msg = cv_ptr->toImageMsg();
00161 }