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 "line_strip_marker.h"
00031 #include "rviz/default_plugin/marker_display.h"
00032 #include "rviz/common.h"
00033 #include "rviz/visualization_manager.h"
00034
00035 #include <ogre_tools/billboard_line.h>
00036
00037 #include <OGRE/OgreVector3.h>
00038 #include <OGRE/OgreQuaternion.h>
00039
00040 namespace rviz
00041 {
00042
00043 LineStripMarker::LineStripMarker(MarkerDisplay* owner, VisualizationManager* manager, Ogre::SceneNode* parent_node)
00044 : MarkerBase(owner, manager, parent_node)
00045 , lines_(0)
00046 {
00047 }
00048
00049 LineStripMarker::~LineStripMarker()
00050 {
00051 delete lines_;
00052 }
00053
00054 void LineStripMarker::onNewMessage(const MarkerConstPtr& old_message, const MarkerConstPtr& new_message)
00055 {
00056 ROS_ASSERT(new_message->type == visualization_msgs::Marker::LINE_STRIP);
00057
00058 if (!lines_)
00059 {
00060 lines_ = new ogre_tools::BillboardLine(vis_manager_->getSceneManager(), parent_node_);
00061 }
00062
00063 Ogre::Vector3 pos, scale;
00064 Ogre::Quaternion orient;
00065 transform(new_message, pos, orient, scale);
00066
00067 lines_->setPosition(pos);
00068 lines_->setOrientation(orient);
00069 lines_->setScale(scale);
00070 lines_->setColor(new_message->color.r, new_message->color.g, new_message->color.b, new_message->color.a);
00071
00072 lines_->clear();
00073 if (new_message->points.empty())
00074 {
00075 return;
00076 }
00077
00078 lines_->setLineWidth(new_message->scale.x);
00079 lines_->setMaxPointsPerLine(new_message->points.size());
00080
00081 bool has_per_point_color = new_message->colors.size() == new_message->points.size();
00082
00083 size_t i = 0;
00084 std::vector<geometry_msgs::Point>::const_iterator it = new_message->points.begin();
00085 std::vector<geometry_msgs::Point>::const_iterator end = new_message->points.end();
00086 for ( ; it != end; ++it, ++i )
00087 {
00088 const geometry_msgs::Point& p = *it;
00089
00090 Ogre::Vector3 v( p.x, p.y, p.z );
00091 robotToOgre( v );
00092
00093 Ogre::ColourValue c;
00094 if (has_per_point_color)
00095 {
00096 const std_msgs::ColorRGBA& color = new_message->colors[i];
00097 c.r = color.r;
00098 c.g = color.g;
00099 c.b = color.b;
00100 c.a = new_message->color.a;
00101 }
00102 else
00103 {
00104 c.r = new_message->color.r;
00105 c.g = new_message->color.g;
00106 c.b = new_message->color.b;
00107 c.a = new_message->color.a;
00108 }
00109
00110 lines_->addPoint( v, c );
00111 }
00112 }
00113
00114 }