36 #include <boost/format.hpp> 45 "frame to visualize trajectory",
51 "duration to visualize trajectory",
57 "color of trajectory",
132 Ogre::Vector3 position;
133 Ogre::Quaternion orientation;
135 header, position, orientation)) {
137 (boost::format(
"Failed transforming from frame '%s' to frame '%s'")
138 % header.frame_id.c_str() % fixed_frame_id.c_str()).
str().c_str());
142 geometry_msgs::PointStamped new_point;
143 new_point.header.stamp = now;
144 new_point.point.x = position[0];
145 new_point.point.y = position[1];
146 new_point.point.z = position[2];
149 for (std::vector<geometry_msgs::PointStamped>::iterator it =
trajectory_.begin();
virtual QColor getColor() const
rviz::TfFrameProperty * frame_property_
std::vector< geometry_msgs::PointStamped > trajectory_
void addPoint(const Ogre::Vector3 &point)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
rviz::FloatProperty * duration_property_
rviz::BillboardLine * line_
virtual float getFloat() const
rviz::ColorProperty * color_property_
rviz::FloatProperty * line_width_property_
virtual ~TFTrajectoryDisplay()
Ogre::SceneNode * scene_node_
virtual void setColor(float r, float g, float b, float a)
virtual FrameManager * getFrameManager() const =0
virtual void onInitialize()
const std::string & getFixedFrame()
void setNumLines(uint32_t num)
void setMaxPointsPerLine(uint32_t max)
virtual Ogre::SceneManager * getSceneManager() const =0
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
virtual void update(float wall_dt, float ros_dt)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
void setLineWidth(float width)