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
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <tf/tf.h>
00040 #include <boost/foreach.hpp>
00041 #include <visualization_msgs/Marker.h>
00042 #include <pole_structure_mapper/PoleSectionStamped.h>
00043 #include <pole_structure_mapper/PoleStructure.h>
00044
00045 #include <tf/transform_listener.h>
00046 #include <tf/message_filter.h>
00047 #include <message_filters/subscriber.h>
00048
00049 ros::Publisher * marker_pub_;
00050
00051 void poleStructureCallback(const pole_structure_mapper::PoleStructure::ConstPtr& msg)
00052 {
00053
00054
00055 pole_structure_mapper::PoleStructure pole_structure_ = *msg;
00056
00057 for(int i=0 ; i<pole_structure_.pole.size() ; i++)
00058 {
00059 char tag[16];
00060 sprintf(tag, "pole_%d", i);
00061
00062
00063 visualization_msgs::Marker marker;
00064 marker.header.frame_id = "map";
00065 marker.header.stamp = ros::Time::now();
00066
00067 marker.ns = tag;
00068 marker.id = 0;
00069
00070 marker.type = visualization_msgs::Marker::CYLINDER;
00071
00072 marker.action = visualization_msgs::Marker::ADD;
00073
00074
00075 marker.pose.position.x = pole_structure_.pole[i].base.x + pole_structure_.pole[i].length/2.0 * pole_structure_.pole[i].axis.x;
00076 marker.pose.position.y = pole_structure_.pole[i].base.y + pole_structure_.pole[i].length/2.0 * pole_structure_.pole[i].axis.y;
00077 marker.pose.position.z = pole_structure_.pole[i].base.z + pole_structure_.pole[i].length/2.0 * pole_structure_.pole[i].axis.z;
00078
00079 tf::Vector3 axis_vector(pole_structure_.pole[i].axis.x, pole_structure_.pole[i].axis.y, pole_structure_.pole[i].axis.z);
00080 tf::Vector3 up_vector(0.0, 0.0, 1.0);
00081 tf::Vector3 right_vector = axis_vector.cross(up_vector);
00082 right_vector.normalized();
00083 tf::Quaternion q(right_vector, -1.0*acos(axis_vector.dot(up_vector)));
00084 q.normalize();
00085 geometry_msgs::Quaternion cylinder_orientation;
00086 tf::quaternionTFToMsg(q, cylinder_orientation);
00087
00088 marker.pose.orientation = cylinder_orientation;
00089
00090 marker.scale.x = pole_structure_.pole[i].diameter;
00091 marker.scale.y = pole_structure_.pole[i].diameter;
00092 marker.scale.z = pole_structure_.pole[i].length;
00093
00094 marker.color.r = 1.0f;
00095 marker.color.g = 0.0f;
00096 marker.color.b = 0.0f;
00097 marker.color.a = 0.8;
00098
00099 marker.lifetime = ros::Duration();
00100
00101
00102 marker_pub_->publish(marker);
00103 }
00104 }
00105
00106 int main(int argc, char** argv)
00107 {
00108 ros::init(argc, argv, "pole_structure_visualizer_node");
00109
00110 ROS_INFO("Pole Structure Visualizer for ROS v0.1");
00111
00112
00113 ros::NodeHandle n;
00114
00115 ros::Subscriber sub = n.subscribe("pole_structure", 1, poleStructureCallback);
00116 ros::Publisher pub = n.advertise<visualization_msgs::Marker>("pole_structure_visualizer", 30);
00117 marker_pub_ = &pub;
00118
00119 ros::spin();
00120
00121 }
00122
00123
00124