effort_visual.cpp
Go to the documentation of this file.
1 #include <OgreVector3.h>
2 #include <OgreSceneNode.h>
3 #include <OgreSceneManager.h>
4 
7 
8 #include <ros/ros.h>
9 
10 #include <urdf/model.h>
11 #include "effort_visual.h"
12 
13 namespace rviz
14 {
15 
16  EffortVisual::EffortVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node, boost::shared_ptr<urdf::Model> urdf_model )
17  {
18  scene_manager_ = scene_manager;
19 
20  // Ogre::SceneNode s form a tree, with each node storing the
21  // transform (position and orientation) of itself relative to its
22  // parent. Ogre does the math of combining those transforms when it
23  // is time to render.
24  //
25  // Here we create a node to store the pose of the Effort's header frame
26  // relative to the RViz fixed frame.
27  frame_node_ = parent_node->createChildSceneNode();
28 
29  //
30  urdf_model_ = urdf_model;
31 
32  // We create the arrow object within the frame node so that we can
33  // set its position and direction relative to its header frame.
34  for (std::map<std::string, urdf::JointSharedPtr >::iterator it = urdf_model_->joints_.begin(); it != urdf_model_->joints_.end(); it ++ ) {
35  if ( it->second->type == urdf::Joint::REVOLUTE ) {
36  std::string joint_name = it->first;
37  effort_enabled_[joint_name] = true;
38  }
39  }
40  }
41 
43  {
44  // Delete the arrow to make it disappear.
45  for (std::map<std::string, rviz::BillboardLine*>::iterator it = effort_circle_.begin(); it != effort_circle_.end(); it ++ ) {
46  delete (it->second);
47  }
48  for (std::map<std::string, rviz::Arrow*>::iterator it = effort_arrow_.begin(); it != effort_arrow_.end(); it ++ ) {
49  delete (it->second);
50  }
51 
52  // Destroy the frame node since we don't need it anymore.
53  scene_manager_->destroySceneNode( frame_node_ );
54  }
55 
56 
57  void EffortVisual::getRainbowColor(float value, Ogre::ColourValue& color)
58  {
59  value = std::min(value, 1.0f);
60  value = std::max(value, 0.0f);
61 
62  float h = value * 5.0f + 1.0f;
63  int i = floor(h);
64  float f = h - i;
65  if ( !(i&1) ) f = 1 - f; // if i is even
66  float n = 1 - f;
67 
68  if (i <= 1) color[0] = n, color[1] = 0, color[2] = 1;
69  else if (i == 2) color[0] = 0, color[1] = n, color[2] = 1;
70  else if (i == 3) color[0] = 0, color[1] = 1, color[2] = n;
71  else if (i == 4) color[0] = n, color[1] = 1, color[2] = 0;
72  else if (i >= 5) color[0] = 1, color[1] = n, color[2] = 0;
73  }
74 
75  void EffortVisual::setMessage( const sensor_msgs::JointStateConstPtr& msg )
76  {
77  // for all joints...
78  int joint_num = msg->name.size();
79  for (int i = 0; i < joint_num; i++ )
80  {
81  std::string joint_name = msg->name[i];
82  double effort = msg->effort[i];
83  const urdf::Joint* joint = urdf_model_->getJoint(joint_name).get();
84  int joint_type = joint->type;
85  if ( joint_type == urdf::Joint::REVOLUTE )
86  {
87  // enable or disable draw
88  if ( effort_circle_.find(joint_name) != effort_circle_.end() &&
89  !effort_enabled_[joint_name] ) // enable->disable
90  {
91  delete(effort_circle_[joint_name]);
92  delete(effort_arrow_[joint_name]);
93  effort_circle_.erase(joint_name);
94  effort_arrow_.erase(joint_name);
95  }
96  if ( effort_circle_.find(joint_name) == effort_circle_.end() &&
97  effort_enabled_[joint_name] ) // disable -> enable
98  {
100  effort_arrow_[joint_name] = new rviz::Arrow( scene_manager_, frame_node_ );
101  }
102 
103  if ( ! effort_enabled_[joint_name] ) continue;
104 
105  //tf::Transform offset = poseFromJoint(joint);
106  urdf::JointLimitsSharedPtr limit = joint->limits;
107  double max_effort = limit->effort, effort_value = 0.05;
108 
109  if ( max_effort != 0.0 )
110  {
111  effort_value = std::min(fabs(effort) / max_effort, 1.0) + 0.05;
112  } else {
113  effort_value = fabs(effort) + 0.05;
114  }
115 
116  effort_arrow_[joint_name]->set(0, width_*2, width_*2*1.0, width_*2*2.0);
117  if ( effort > 0 ) {
118  effort_arrow_[joint_name]->setDirection(orientation_[joint_name] * Ogre::Vector3(-1,0,0));
119  } else {
120  effort_arrow_[joint_name]->setDirection(orientation_[joint_name] * Ogre::Vector3( 1,0,0));
121  }
122  effort_arrow_[joint_name]->setPosition(orientation_[joint_name] * Ogre::Vector3(0, 0.05+effort_value*scale_*0.5, 0) + position_[joint_name]);
123  effort_circle_[joint_name]->clear();
124  effort_circle_[joint_name]->setLineWidth(width_);
125  for (int i = 0; i < 30; i++) {
126  Ogre::Vector3 point = Ogre::Vector3((0.05+effort_value*scale_*0.5)*sin(i*2*M_PI/32), (0.05+effort_value*scale_*0.5)*cos(i*2*M_PI/32), 0);
127  if ( effort < 0 ) point.x = -point.x;
128  effort_circle_[joint_name]->addPoint(orientation_[joint_name] * point + position_[joint_name]);
129  }
130  Ogre::ColourValue color;
131  getRainbowColor(effort_value, color);
132  effort_arrow_[joint_name]->setColor(color.r, color.g, color.b, color.a);
133  effort_circle_[joint_name]->setColor(color.r, color.g, color.b, color.a);
134  }
135  }
136  }
137 
138  void EffortVisual::setFrameEnabled( const std::string joint_name, const bool e )
139  {
140  effort_enabled_[joint_name] = e;
141  }
142 
143  // Position and orientation are passed through to the SceneNode.
144  void EffortVisual::setFramePosition( const Ogre::Vector3& position )
145  {
146  frame_node_->setPosition( position );
147  }
148 
149  void EffortVisual::setFrameOrientation( const Ogre::Quaternion& orientation )
150  {
151  frame_node_->setOrientation( orientation );
152  }
153  // Position and orientation are passed through to the SceneNode.
154  void EffortVisual::setFramePosition( const std::string joint_name, const Ogre::Vector3& position )
155  {
156  position_[joint_name] = position;
157  }
158 
159  void EffortVisual::setFrameOrientation( const std::string joint_name, const Ogre::Quaternion& orientation )
160  {
161  orientation_[joint_name] = orientation;
162  }
163 
164  void EffortVisual::setWidth( float w )
165  {
166  width_ = w;
167  }
168 
169  void EffortVisual::setScale( float s )
170  {
171  scale_ = s;
172  }
173 
174 } // end namespace rviz
175 
std::map< std::string, Ogre::Quaternion > orientation_
Definition: effort_visual.h:83
void getRainbowColor(float value, Ogre::ColourValue &color)
void setMessage(const sensor_msgs::JointStateConstPtr &msg)
f
An object that displays a multi-segment line strip rendered as billboards.
static int limit(int i)
Definition: parse_color.cpp:35
void setFramePosition(const Ogre::Vector3 &position)
std::map< std::string, rviz::Arrow * > effort_arrow_
Definition: effort_visual.h:71
Ogre::SceneNode * frame_node_
Definition: effort_visual.h:76
std::map< std::string, Ogre::Vector3 > position_
Definition: effort_visual.h:82
void setScale(float s)
void setWidth(float w)
std::map< std::string, rviz::BillboardLine * > effort_circle_
Definition: effort_visual.h:70
Ogre::SceneManager * scene_manager_
Definition: effort_visual.h:80
std::map< std::string, bool > effort_enabled_
Definition: effort_visual.h:72
EffortVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node, boost::shared_ptr< urdf::Model > urdf_model)
void setFrameEnabled(const std::string joint_name, const bool e)
void setFrameOrientation(const Ogre::Quaternion &orientation)
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:59
boost::shared_ptr< urdf::Model > urdf_model_
Definition: effort_visual.h:88


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51