Go to the documentation of this file.00001 #include <OgreVector3.h>
00002 #include <OgreSceneNode.h>
00003 #include <OgreSceneManager.h>
00004
00005 #include <rviz/ogre_helpers/arrow.h>
00006 #include <rviz/ogre_helpers/billboard_line.h>
00007
00008 #include <ros/ros.h>
00009
00010 #include "wrench_visual.h"
00011
00012 namespace rviz
00013 {
00014
00015 WrenchStampedVisual::WrenchStampedVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node )
00016 {
00017 scene_manager_ = scene_manager;
00018
00019
00020
00021
00022
00023
00024
00025
00026 frame_node_ = parent_node->createChildSceneNode();
00027
00028
00029
00030 arrow_force_ = new rviz::Arrow( scene_manager_, frame_node_ );
00031 arrow_torque_ = new rviz::Arrow( scene_manager_, frame_node_ );
00032 circle_torque_ = new rviz::BillboardLine( scene_manager_, frame_node_ );
00033 circle_arrow_torque_ = new rviz::Arrow( scene_manager_, frame_node_ );
00034 }
00035
00036 WrenchStampedVisual::~WrenchStampedVisual()
00037 {
00038
00039 delete arrow_force_;
00040 delete arrow_torque_;
00041 delete circle_torque_;
00042 delete circle_arrow_torque_;
00043
00044
00045 scene_manager_->destroySceneNode( frame_node_ );
00046 }
00047
00048
00049 void WrenchStampedVisual::setMessage( const geometry_msgs::WrenchStamped::ConstPtr& msg )
00050 {
00051 Ogre::Vector3 force(msg->wrench.force.x, msg->wrench.force.y, msg->wrench.force.z);
00052 Ogre::Vector3 torque(msg->wrench.torque.x, msg->wrench.torque.y, msg->wrench.torque.z);
00053 double force_length = force.length() * force_scale_;
00054 double torque_length = torque.length() * torque_scale_;
00055 arrow_force_->setScale(Ogre::Vector3(force_length, width_, width_));
00056 arrow_torque_->setScale(Ogre::Vector3(torque_length, width_, width_));
00057
00058 arrow_force_->setDirection(force);
00059 arrow_torque_->setDirection(torque);
00060 Ogre::Vector3 axis_z(0,0,1);
00061 Ogre::Quaternion orientation = axis_z.getRotationTo(torque);
00062 if ( std::isnan(orientation.x) ||
00063 std::isnan(orientation.y) ||
00064 std::isnan(orientation.z) ) orientation = Ogre::Quaternion::IDENTITY;
00065
00066 circle_arrow_torque_->set(0, width_*0.1, width_*0.1*1.0, width_*0.1*2.0);
00067 circle_arrow_torque_->setDirection(orientation * Ogre::Vector3(0,1,0));
00068 circle_arrow_torque_->setPosition(orientation * Ogre::Vector3(torque_length/4, 0, torque_length/2));
00069 circle_torque_->clear();
00070 circle_torque_->setLineWidth(width_*0.05);
00071 for (int i = 4; i <= 32; i++) {
00072 Ogre::Vector3 point = Ogre::Vector3((torque_length/4)*cos(i*2*M_PI/32),
00073 (torque_length/4)*sin(i*2*M_PI/32),
00074 torque_length/2);
00075 circle_torque_->addPoint(orientation * point);
00076 }
00077 }
00078
00079
00080 void WrenchStampedVisual::setFramePosition( const Ogre::Vector3& position )
00081 {
00082 frame_node_->setPosition( position );
00083 }
00084
00085 void WrenchStampedVisual::setFrameOrientation( const Ogre::Quaternion& orientation )
00086 {
00087 frame_node_->setOrientation( orientation );
00088 }
00089
00090
00091 void WrenchStampedVisual::setForceColor( float r, float g, float b, float a )
00092 {
00093 arrow_force_->setColor( r, g, b, a );
00094 }
00095
00096 void WrenchStampedVisual::setTorqueColor( float r, float g, float b, float a )
00097 {
00098 arrow_torque_->setColor( r, g, b, a );
00099 circle_torque_->setColor( r, g, b, a );
00100 circle_arrow_torque_->setColor( r, g, b, a );
00101 }
00102
00103 void WrenchStampedVisual::setForceScale( float s )
00104 {
00105 force_scale_ = s;
00106 }
00107
00108 void WrenchStampedVisual::setTorqueScale( float s )
00109 {
00110 torque_scale_ = s;
00111 }
00112
00113 void WrenchStampedVisual::setWidth( float w )
00114 {
00115 width_ = w;
00116 }
00117
00118 }
00119