38 #include <OGRE/OgreCamera.h> 39 #include <OGRE/OgreMaterialManager.h> 41 #include <OGRE/OgreManualObject.h> 49 message_recieved_(false)
52 "target name",
"target",
58 "radius of the target mark",
63 "0 is fully transparent, 1.0 is fully opaque.",
68 "color", QColor(25, 255, 240),
69 "color of the target",
72 "type",
"Simple Circle",
73 "Shape to display the pose as",
95 const geometry_msgs::PoseStamped::ConstPtr& msg)
103 Ogre::Quaternion orientation;
104 Ogre::Vector3 position;
107 position, orientation))
109 std::ostringstream oss;
110 oss <<
"Error transforming pose";
111 oss <<
" from frame '" << msg->header.frame_id <<
"'";
112 oss <<
" to frame '" << qPrintable(
fixed_frame_) <<
"'";
virtual QColor getColor() const
virtual void onInitialize()
rviz::ColorProperty * color_property_
rviz::FloatProperty * alpha_property_
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
virtual float getFloat() const
rviz::FloatProperty * radius_property_
const double minimum_font_size
TargetVisualizerDisplay()
Ogre::SceneNode * scene_node_
std::string getStdString()
bool visualizer_initialized_
virtual void addOption(const QString &option, int value=0)
rviz::StringProperty * target_name_property_
virtual void setAnonymous(bool anonymous)
const float arrow_animation_duration
rviz::EnumProperty * shape_type_property_
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
virtual FrameManager * getFrameManager() const =0
void update(float wall_dt, float ros_dt)
Ogre::SceneManager * scene_manager_
virtual void onInitialize()
FacingObject::Ptr visualizer_
void processMessage(const geometry_msgs::PoseStamped::ConstPtr &msg)
virtual ~TargetVisualizerDisplay()
#define ROS_ERROR_STREAM(args)
virtual int getOptionInt()
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)