40   TwistStampedDisplay::TwistStampedDisplay()
 
   43                                                      "linear velocity scale",
 
   44                                                      this, SLOT(updateLinearScale()));
 
   46                                                       "angular velocity scale",
 
   47                                                      this, SLOT(updateAngularScale()));
 
   49                                                      "linear velocity color",
 
   50                                                      this, SLOT(updateLinearColor()));
 
   52                                                       "angular velocity color",
 
   53                                                      this, SLOT(updateAngularColor()));
 
   58   TwistStampedDisplay::~TwistStampedDisplay()
 
   67     linear_arrow_.reset(
new rviz::Arrow(scene_manager_, scene_node_));
 
   71     x_rotate_arrow_.reset(
new rviz::Arrow(scene_manager_, scene_node_));
 
   72     y_rotate_arrow_.reset(
new rviz::Arrow(scene_manager_, scene_node_));
 
   73     z_rotate_arrow_.reset(
new rviz::Arrow(scene_manager_, scene_node_));
 
   78     Ogre::Vector3 zero_scale(0, 0, 0);
 
   79     linear_arrow_->setScale(zero_scale);
 
   80     x_rotate_arrow_->set(0, 0, 0, 0);
 
   81     y_rotate_arrow_->set(0, 0, 0, 0);
 
   82     z_rotate_arrow_->set(0, 0, 0, 0);
 
   91     const geometry_msgs::TwistStamped::ConstPtr& msg)
 
   94     Ogre::Vector3 position;
 
   95     Ogre::Quaternion orientation;
 
   96     if(!context_->getFrameManager()->getTransform(
 
   97          msg->header, position, orientation)) {
 
   98       ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
 
   99                 msg->header.frame_id.c_str(), qPrintable(fixed_frame_));
 
  102     scene_node_->setPosition(position);
 
  103     scene_node_->setOrientation(orientation);
 
  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(),
 
  108                                linear_scale_ * linear_direction.length(),
 
  109                                linear_scale_ * linear_direction.length());
 
  110     linear_arrow_->setScale(linear_scale);
 
  111     linear_arrow_->setDirection(linear_direction);
 
  114     updateRotationVelocity(x_rotate_circle_,
 
  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);
 
  121     updateRotationVelocity(y_rotate_circle_,
 
  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);
 
  128     updateRotationVelocity(z_rotate_circle_,
 
  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);
 
  136     x_rotate_circle_->setColor(c.r, c.g, c.b, 1.0);
 
  137     y_rotate_circle_->setColor(c.r, c.g, c.b, 1.0);
 
  138     z_rotate_circle_->setColor(c.r, c.g, c.b, 1.0);
 
  139     x_rotate_arrow_->setColor(c);
 
  140     y_rotate_arrow_->setColor(c);
 
  141     z_rotate_arrow_->setColor(c);
 
  144   void TwistStampedDisplay::updateRotationVelocity(
 
  145       BillboardLinePtr circle,
 
  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); 
 
  162     circle->setLineWidth(
r * angular_scale_ / 2 * 0.1);
 
  164       double rad = 
theta / 180 * M_PI;
 
  165       Ogre::Vector3 
p = ux * cos(rad) * 
r * angular_scale_ + uy * sin(rad) * 
r * angular_scale_;
 
  170       double end_rad = (end_theta - 
step) / 180 * M_PI;
 
  171       Ogre::Vector3 endpoint = ux * cos(end_rad) * 
r * angular_scale_ + uy * sin(end_rad) * 
r * angular_scale_;
 
  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;
 
  178       Ogre::Vector3 endpoint = ux * cos(end_rad) * 
r * angular_scale_ + uy * sin(end_rad) * 
r * angular_scale_;
 
  179       Ogre::Vector3 direction = - ux * (- sin(end_rad)) - uy * cos(end_rad);
 
  180       arrow->setPosition(endpoint);
 
  181       arrow->setDirection(direction);
 
  183     arrow->set(0, 0, 
r * angular_scale_ / 2, 
r * angular_scale_ / 2);
 
  189   void TwistStampedDisplay::updateLinearScale()
 
  194   void TwistStampedDisplay::updateAngularScale()
 
  199   void TwistStampedDisplay::updateLinearColor()
 
  204   void TwistStampedDisplay::updateAngularColor()