30 #ifndef HECTOR_RVIZ_PLUGINS_VECTOR3_DISPLAY_H 31 #define HECTOR_RVIZ_PLUGINS_VECTOR3_DISPLAY_H 33 #include <boost/shared_ptr.hpp> 34 #include <boost/thread/mutex.hpp> 41 #include <geometry_msgs/Vector3Stamped.h> 52 class RosTopicProperty;
53 class TfFrameProperty;
75 virtual void onInitialize();
76 virtual void fixedFrameChanged();
77 virtual void update(
float wall_dt,
float ros_dt );
82 virtual void onEnable();
83 virtual void onDisable();
88 void updateOriginFrame();
97 void incomingMessage(
const geometry_msgs::Vector3Stamped::ConstPtr& message );
98 void transformArrow(
const geometry_msgs::Vector3Stamped::ConstPtr& message,
Arrow* arrow );
122 #endif // HECTOR_RVIZ_PLUGINS_VECTOR3_DISPLAY_H
uint32_t messages_received_
message_filters::Subscriber< geometry_msgs::Vector3Stamped > sub_
ColorProperty * color_property_
TfFrameProperty * origin_frame_property_
boost::shared_ptr< Ogre::Quaternion > last_orientation_
boost::shared_ptr< Ogre::Vector3 > last_position_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
FloatProperty * angle_tolerance_property_
FloatProperty * position_tolerance_property_
TFSIMD_FORCE_INLINE Vector3()
FloatProperty * scale_property_
RosTopicProperty * topic_property_
std::deque< Arrow * > D_Arrow
tf::MessageFilter< geometry_msgs::Vector3Stamped > * tf_filter_
IntProperty * keep_property_