43 "linear velocity scale",
46 "angular velocity scale",
49 "linear velocity color",
52 "angular velocity color",
78 Ogre::Vector3 zero_scale(0, 0, 0);
91 const geometry_msgs::TwistStamped::ConstPtr& msg)
94 Ogre::Vector3 position;
95 Ogre::Quaternion orientation;
97 msg->header, position, orientation)) {
98 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
106 Ogre::Vector3 linear_direction(msg->twist.linear.x, msg->twist.linear.y, msg->twist.linear.z);
107 Ogre::Vector3 linear_scale(
linear_scale_ * linear_direction.length(),
116 Ogre::Vector3(0, 1, 0),
117 Ogre::Vector3(0, 0, 1),
118 Ogre::Vector3(1, 0, 0),
119 std::abs(msg->twist.angular.x),
120 msg->twist.angular.x > 0);
123 Ogre::Vector3(0, 0, 1),
124 Ogre::Vector3(1, 0, 0),
125 Ogre::Vector3(0, 1, 0),
126 std::abs(msg->twist.angular.y),
127 msg->twist.angular.y > 0);
130 Ogre::Vector3(1, 0, 0),
131 Ogre::Vector3(0, 1, 0),
132 Ogre::Vector3(0, 0, 1),
133 std::abs(msg->twist.angular.z),
134 msg->twist.angular.z > 0);
147 const Ogre::Vector3& ux,
148 const Ogre::Vector3& uy,
149 const Ogre::Vector3& uz,
155 arrow->set(0, 0, 0, 0);
158 const double step = 10;
159 const double start_theta = 20;
160 const double end_theta = 340;
161 circle->setMaxPointsPerLine((end_theta - start_theta) / step + 1);
164 double rad =
theta / 180 * M_PI;
170 double end_rad = (end_theta - step) / 180 * M_PI;
172 Ogre::Vector3 direction = ux * (-
sin(end_rad)) + uy *
cos(end_rad);
173 arrow->setPosition(endpoint);
174 arrow->setDirection(direction);
177 double end_rad = (start_theta + step) / 180 * M_PI;
179 Ogre::Vector3 direction = - ux * (-
sin(end_rad)) - uy *
cos(end_rad);
180 arrow->setPosition(endpoint);
181 arrow->setDirection(direction);
virtual QColor getColor() const
rviz::ColorProperty * angular_color_property_
rviz::ColorProperty * linear_color_property_
BillboardLinePtr z_rotate_circle_
virtual void onInitialize()
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
BillboardLinePtr y_rotate_circle_
BillboardLinePtr x_rotate_circle_
virtual float getFloat() const
virtual ~TwistStampedDisplay()
void updateAngularScale()
Ogre::SceneNode * scene_node_
Ogre::ColourValue qtToOgre(const QColor &c)
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)
virtual FrameManager * getFrameManager() const =0
void updateAngularColor()
Ogre::SceneManager * scene_manager_
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
virtual void onInitialize()
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
rviz::FloatProperty * linear_scale_property_
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
rviz::FloatProperty * angular_scale_property_