31 #include <boost/bind.hpp> 52 , messages_received_( 0 )
55 QString::fromStdString( ros::message_traits::datatype<geometry_msgs::Vector3Stamped>() ),
56 "geometry_msgs::Vector3Stamped topic to subscribe to.",
60 "Color of the arrows.",
64 "Frame that defines the origin of the vector.",
70 "Distance, in meters from the last arrow dropped, " 71 "that will cause a new arrow to drop.",
76 "Angular distance from the last arrow dropped, " 77 "that will cause a new arrow to drop.",
82 "Scale of each arrow.",
86 "Number of arrows to keep before removing the oldest. 0 means keep all of them.",
113 D_Arrow::iterator it =
arrows_.begin();
114 D_Arrow::iterator end =
arrows_.end();
115 for ( ; it != end; ++it )
141 float red = color.redF();
142 float green = color.greenF();
143 float blue = color.blueF();
145 D_Arrow::iterator it =
arrows_.begin();
146 D_Arrow::iterator end =
arrows_.end();
147 for( ; it != end; ++it )
150 arrow->
setColor( red, green, blue, 1.0
f );
215 Ogre::Quaternion orientation, fake_orientation;
216 Ogre::Vector3 position, fake_position;
218 message->header.stamp,
219 position, fake_orientation ))
221 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
227 message->header.stamp,
228 fake_position, orientation ))
230 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
231 message->header.frame_id.c_str(), qPrintable(
fixed_frame_ ) );
235 Ogre::Vector3 vector( message->vector.x, message->vector.y, -message->vector.z );
236 orientation = orientation * vector.getRotationTo(Ogre::Vector3::UNIT_Z);
247 float length = vector.length();
254 arrow->
setColor( color.redF(), color.greenF(), color.blueF(), 1.0f );
virtual QColor getColor() const
virtual tf::TransformListener * getTFClient() const =0
uint32_t messages_received_
DisplayContext * context_
message_filters::Subscriber< geometry_msgs::Vector3Stamped > sub_
virtual int getInt() const
ros::NodeHandle update_nh_
virtual void fixedFrameChanged()
virtual float getFloat() const
ColorProperty * color_property_
virtual void update(float wall_dt, float ros_dt)
TfFrameProperty * origin_frame_property_
virtual ~Vector3Display()
boost::shared_ptr< Ogre::Quaternion > last_orientation_
Ogre::SceneNode * scene_node_
boost::shared_ptr< Ogre::Vector3 > last_position_
std::string getStdString()
FloatProperty * angle_tolerance_property_
virtual void setPosition(const Ogre::Vector3 &position)
FloatProperty * position_tolerance_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void setScale(const Ogre::Vector3 &scale)
void registerFilterForTransformStatusCheck(tf::MessageFilter< M > *filter, Display *display)
virtual void setColor(float r, float g, float b, float a)
FloatProperty * scale_property_
virtual FrameManager * getFrameManager() const =0
virtual void setOrientation(const Ogre::Quaternion &orientation)
void incomingMessage(const geometry_msgs::Vector3Stamped::ConstPtr &message)
Ogre::SceneManager * scene_manager_
virtual void queueRender()=0
RosTopicProperty * topic_property_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
void setTargetFrame(const std::string &target_frame)
std::string getTopicStd() const
virtual void onInitialize()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::MessageFilter< geometry_msgs::Vector3Stamped > * tf_filter_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
IntProperty * keep_property_
Connection registerCallback(const C &callback)