37 #ifndef JSK_RVIZ_PLUGINS_TWIST_STAMPED_H_ 38 #define JSK_RVIZ_PLUGINS_TWIST_STAMPED_H_ 49 #include <OGRE/OgreSceneNode.h> 51 #include <geometry_msgs/TwistStamped.h> 63 #if ROS_VERSION_MINIMUM(1,12,0) 64 typedef std::shared_ptr<rviz::Arrow>
ArrowPtr;
77 const geometry_msgs::TwistStamped::ConstPtr& msg);
79 BillboardLinePtr circle,
81 const Ogre::Vector3& ux,
82 const Ogre::Vector3& uy,
83 const Ogre::Vector3& uz,
rviz::ColorProperty * angular_color_property_
rviz::ColorProperty * linear_color_property_
BillboardLinePtr z_rotate_circle_
boost::shared_ptr< rviz::BillboardLine > BillboardLinePtr
BillboardLinePtr y_rotate_circle_
BillboardLinePtr x_rotate_circle_
boost::shared_ptr< rviz::Arrow > ArrowPtr
virtual ~TwistStampedDisplay()
void updateAngularScale()
virtual void updateRotationVelocity(BillboardLinePtr circle, ArrowPtr arrow, const Ogre::Vector3 &ux, const Ogre::Vector3 &uy, const Ogre::Vector3 &uz, const double r, bool positive)
virtual void processMessage(const geometry_msgs::TwistStamped::ConstPtr &msg)
void updateAngularColor()
virtual void onInitialize()
rviz::FloatProperty * linear_scale_property_
rviz::FloatProperty * angular_scale_property_