00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "twist_stamped_display.h"
00037
00038 namespace jsk_rviz_plugins
00039 {
00040 TwistStampedDisplay::TwistStampedDisplay()
00041 {
00042 linear_scale_property_ = new rviz::FloatProperty("linear scale", 1.0,
00043 "linear velocity scale",
00044 this, SLOT(updateLinearScale()));
00045 angular_scale_property_ = new rviz::FloatProperty("angular scale", 1.0,
00046 "angular velocity scale",
00047 this, SLOT(updateAngularScale()));
00048 linear_color_property_ = new rviz::ColorProperty("linear color", QColor(0, 255, 0),
00049 "linear velocity color",
00050 this, SLOT(updateLinearColor()));
00051 angular_color_property_ = new rviz::ColorProperty("angular color", QColor(255, 0, 0),
00052 "angular velocity color",
00053 this, SLOT(updateAngularColor()));
00054 linear_scale_property_->setMin(0.0);
00055 angular_scale_property_->setMin(0.0);
00056 }
00057
00058 TwistStampedDisplay::~TwistStampedDisplay()
00059 {
00060 delete linear_color_property_;
00061 delete angular_color_property_;
00062 }
00063
00064 void TwistStampedDisplay::onInitialize()
00065 {
00066 MFDClass::onInitialize();
00067 linear_arrow_.reset(new rviz::Arrow(scene_manager_, scene_node_));
00068 x_rotate_circle_.reset(new rviz::BillboardLine(scene_manager_, scene_node_));
00069 y_rotate_circle_.reset(new rviz::BillboardLine(scene_manager_, scene_node_));
00070 z_rotate_circle_.reset(new rviz::BillboardLine(scene_manager_, scene_node_));
00071 x_rotate_arrow_.reset(new rviz::Arrow(scene_manager_, scene_node_));
00072 y_rotate_arrow_.reset(new rviz::Arrow(scene_manager_, scene_node_));
00073 z_rotate_arrow_.reset(new rviz::Arrow(scene_manager_, scene_node_));
00074 updateLinearScale();
00075 updateAngularScale();
00076 updateLinearColor();
00077 updateAngularColor();
00078 Ogre::Vector3 zero_scale(0, 0, 0);
00079 linear_arrow_->setScale(zero_scale);
00080 x_rotate_arrow_->set(0, 0, 0, 0);
00081 y_rotate_arrow_->set(0, 0, 0, 0);
00082 z_rotate_arrow_->set(0, 0, 0, 0);
00083 }
00084
00085 void TwistStampedDisplay::reset()
00086 {
00087 MFDClass::reset();
00088 }
00089
00090 void TwistStampedDisplay::processMessage(
00091 const geometry_msgs::TwistStamped::ConstPtr& msg)
00092 {
00093
00094 Ogre::Vector3 position;
00095 Ogre::Quaternion orientation;
00096 if(!context_->getFrameManager()->getTransform(
00097 msg->header, position, orientation)) {
00098 ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
00099 msg->header.frame_id.c_str(), qPrintable(fixed_frame_));
00100 return;
00101 }
00102 scene_node_->setPosition(position);
00103 scene_node_->setOrientation(orientation);
00104
00105 linear_arrow_->setColor(rviz::qtToOgre(linear_color_));
00106 Ogre::Vector3 linear_direction(msg->twist.linear.x, msg->twist.linear.y, msg->twist.linear.z);
00107 Ogre::Vector3 linear_scale(linear_scale_ * linear_direction.length(),
00108 linear_scale_ * linear_direction.length(),
00109 linear_scale_ * linear_direction.length());
00110 linear_arrow_->setScale(linear_scale);
00111 linear_arrow_->setDirection(linear_direction);
00112
00113
00114 updateRotationVelocity(x_rotate_circle_,
00115 x_rotate_arrow_,
00116 Ogre::Vector3(0, 1, 0),
00117 Ogre::Vector3(0, 0, 1),
00118 Ogre::Vector3(1, 0, 0),
00119 std::abs(msg->twist.angular.x),
00120 msg->twist.angular.x > 0);
00121 updateRotationVelocity(y_rotate_circle_,
00122 y_rotate_arrow_,
00123 Ogre::Vector3(0, 0, 1),
00124 Ogre::Vector3(1, 0, 0),
00125 Ogre::Vector3(0, 1, 0),
00126 std::abs(msg->twist.angular.y),
00127 msg->twist.angular.y > 0);
00128 updateRotationVelocity(z_rotate_circle_,
00129 z_rotate_arrow_,
00130 Ogre::Vector3(1, 0, 0),
00131 Ogre::Vector3(0, 1, 0),
00132 Ogre::Vector3(0, 0, 1),
00133 std::abs(msg->twist.angular.z),
00134 msg->twist.angular.z > 0);
00135 Ogre::ColourValue c = rviz::qtToOgre(angular_color_);
00136 x_rotate_circle_->setColor(c.r, c.g, c.b, 1.0);
00137 y_rotate_circle_->setColor(c.r, c.g, c.b, 1.0);
00138 z_rotate_circle_->setColor(c.r, c.g, c.b, 1.0);
00139 x_rotate_arrow_->setColor(c);
00140 y_rotate_arrow_->setColor(c);
00141 z_rotate_arrow_->setColor(c);
00142 }
00143
00144 void TwistStampedDisplay::updateRotationVelocity(
00145 BillboardLinePtr circle,
00146 ArrowPtr arrow,
00147 const Ogre::Vector3& ux,
00148 const Ogre::Vector3& uy,
00149 const Ogre::Vector3& uz,
00150 const double r,
00151 bool positive)
00152 {
00153 circle->clear();
00154 if (r < 1.0e-9) {
00155 arrow->set(0, 0, 0, 0);
00156 return;
00157 }
00158 const double step = 10;
00159 const double start_theta = 20;
00160 const double end_theta = 340;
00161 circle->setMaxPointsPerLine((end_theta - start_theta) / step + 1);
00162 circle->setLineWidth(r * angular_scale_ / 2 * 0.1);
00163 for (double theta = start_theta; theta < end_theta; theta += step) {
00164 double rad = theta / 180 * M_PI;
00165 Ogre::Vector3 p = ux * cos(rad) * r * angular_scale_ + uy * sin(rad) * r * angular_scale_;
00166 circle->addPoint(p);
00167 }
00168
00169 if (positive) {
00170 double end_rad = (end_theta - step) / 180 * M_PI;
00171 Ogre::Vector3 endpoint = ux * cos(end_rad) * r * angular_scale_ + uy * sin(end_rad) * r * angular_scale_;
00172 Ogre::Vector3 direction = ux * (- sin(end_rad)) + uy * cos(end_rad);
00173 arrow->setPosition(endpoint);
00174 arrow->setDirection(direction);
00175 }
00176 else {
00177 double end_rad = (start_theta + step) / 180 * M_PI;
00178 Ogre::Vector3 endpoint = ux * cos(end_rad) * r * angular_scale_ + uy * sin(end_rad) * r * angular_scale_;
00179 Ogre::Vector3 direction = - ux * (- sin(end_rad)) - uy * cos(end_rad);
00180 arrow->setPosition(endpoint);
00181 arrow->setDirection(direction);
00182 }
00183 arrow->set(0, 0, r * angular_scale_ / 2, r * angular_scale_ / 2);
00184 }
00185
00187
00189 void TwistStampedDisplay::updateLinearScale()
00190 {
00191 linear_scale_ = linear_scale_property_->getFloat();
00192 }
00193
00194 void TwistStampedDisplay::updateAngularScale()
00195 {
00196 angular_scale_ = angular_scale_property_->getFloat();
00197 }
00198
00199 void TwistStampedDisplay::updateLinearColor()
00200 {
00201 linear_color_ = linear_color_property_->getColor();
00202 }
00203
00204 void TwistStampedDisplay::updateAngularColor()
00205 {
00206 angular_color_ = angular_color_property_->getColor();
00207 }
00208 }
00209
00210 #include <pluginlib/class_list_macros.h>
00211 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::TwistStampedDisplay, rviz::Display )