effort_display.cpp
Go to the documentation of this file.
1 #include <OgreSceneNode.h>
2 #include <OgreSceneManager.h>
3 
5 
10 #include <rviz/frame_manager.h>
11 
12 #include <boost/foreach.hpp>
13 
14 #include "effort_visual.h"
15 
16 #include "effort_display.h"
17 
18 #include <urdf/model.h>
19 
20 namespace rviz
21 {
22 
23  JointInfo::JointInfo(const std::string name, rviz::Property* parent_category) {
24  name_ = name;
25  effort_ = 0;
26  max_effort_ = 0;
28 
29  //info->category_ = new Property( QString::fromStdString( info->name_ ) , QVariant(), "", joints_category_);
30  category_ = new rviz::Property( QString::fromStdString( name_ ) , true, "", parent_category, SLOT( updateVisibility() ), this);
31 
32  effort_property_ = new rviz::FloatProperty( "Effort", 0, "Effort value of this joint.", category_);
34 
35  max_effort_property_ = new rviz::FloatProperty( "Max Effort", 0, "Max Effort value of this joint.", category_);
37  }
38 
40  }
41 
43  bool enabled = getEnabled();
44  }
45 
46  void JointInfo::setEffort(double e) {
48  effort_ = e;
49  }
50  double JointInfo::getEffort() { return effort_; }
51  void JointInfo::setMaxEffort(double m) {
53  max_effort_ = m;
54  }
55  double JointInfo::getMaxEffort() { return max_effort_; }
56 
57  bool JointInfo::getEnabled() const
58  {
59  return category_->getValue().toBool();
60  }
61 
62  JointInfo* EffortDisplay::getJointInfo( const std::string& joint)
63  {
64  M_JointInfo::iterator it = joints_.find( joint );
65  if ( it == joints_.end() )
66  {
67  return NULL;
68  }
69 
70  return it->second;
71  }
72 
73  JointInfo* EffortDisplay::createJoint(const std::string &joint)
74  {
75  JointInfo *info = new JointInfo(joint, joints_category_);
76  joints_.insert( std::make_pair( joint, info ) );
77  return info;
78  }
79 
82  {
83  alpha_property_ =
84  new rviz::FloatProperty( "Alpha", 1.0,
85  "0 is fully transparent, 1.0 is fully opaque.",
86  this, SLOT( updateColorAndAlpha() ));
87 
88  width_property_ =
89  new rviz::FloatProperty( "Width", 0.02,
90  "Width to drow effort circle",
91  this, SLOT( updateColorAndAlpha() ));
92 
93  scale_property_ =
94  new rviz::FloatProperty( "Scale", 1.0,
95  "Scale to drow effort circle",
96  this, SLOT( updateColorAndAlpha() ));
97 
98  history_length_property_ =
99  new rviz::IntProperty( "History Length", 1,
100  "Number of prior measurements to display.",
101  this, SLOT( updateHistoryLength() ));
102  history_length_property_->setMin( 1 );
103  history_length_property_->setMax( 100000 );
104 
105 
106  robot_description_property_ =
107  new rviz::StringProperty( "Robot Description", "robot_description",
108  "Name of the parameter to search for to load the robot description.",
109  this, SLOT( updateRobotDescription() ) );
110 
111 
112  joints_category_ =
113  new rviz::Property("Joints", QVariant(), "", this);
114  }
115 
117  {
118  MFDClass::onInitialize();
119  updateHistoryLength();
120  }
121 
123  {
124  //delete robot_model_; // sharead pointer
125  }
126 
127  // Clear the visuals by deleting their objects.
129  {
130  MFDClass::reset();
131  visuals_.clear();
132  }
133 
135  {
136  clearStatuses();
137  robot_description_.clear();
138  }
139 
140  // Set the current color and alpha values for each visual.
142  {
143  float width = width_property_->getFloat();
144  float scale = scale_property_->getFloat();
145 
146  for( size_t i = 0; i < visuals_.size(); i++ )
147  {
148  visuals_[ i ]->setWidth( width );
149  visuals_[ i ]->setScale( scale );
150  }
151  }
152 
154  {
155  if( isEnabled() )
156  {
157  load();
158  context_->queueRender();
159  }
160  }
161 
162  // Set the number of past visuals to show.
164  {
165  visuals_.rset_capacity(history_length_property_->getInt());
166  }
167 
169  {
170  // get robot_description
171  std::string content;
172  if (!update_nh_.getParam( robot_description_property_->getStdString(), content) ) {
173  std::string loc;
174  if( update_nh_.searchParam( robot_description_property_->getStdString(), loc ))
175  {
176  update_nh_.getParam( loc, content );
177  }
178  else
179  {
180  clear();
181  setStatus( rviz::StatusProperty::Error, "URDF",
182  "Parameter [" + robot_description_property_->getString()
183  + "] does not exist, and was not found by searchParam()" );
184  return;
185  }
186  }
187 
188  if( content.empty() )
189  {
190  clear();
191  setStatus( rviz::StatusProperty::Error, "URDF", "URDF is empty" );
192  return;
193  }
194 
195  if( content == robot_description_ )
196  {
197  return;
198  }
199 
200  robot_description_ = content;
201 
202 
203  robot_model_ = boost::shared_ptr<urdf::Model>(new urdf::Model());
204  if (!robot_model_->initString(content))
205  {
206  ROS_ERROR("Unable to parse URDF description!");
207  setStatus( rviz::StatusProperty::Error, "URDF", "Unable to parse robot model description!");
208  return;
209  }
210  setStatus(rviz::StatusProperty::Ok, "URDF", "Robot model parserd Ok");
211  for (std::map<std::string, urdf::JointSharedPtr >::iterator it = robot_model_->joints_.begin(); it != robot_model_->joints_.end(); it ++ ) {
212  urdf::JointSharedPtr joint = it->second;
213  if ( joint->type == urdf::Joint::REVOLUTE ) {
214  std::string joint_name = it->first;
215  urdf::JointLimitsSharedPtr limit = joint->limits;
216  joints_[joint_name] = createJoint(joint_name);
217  joints_[joint_name]->setMaxEffort(limit->effort);
218  }
219  }
220  }
221 
223  {
224  load();
225  }
226 
228  {
229  clear();
230  }
231 
232 #if 0
233  void EffortDisplay::setRobotDescription( const std::string& description_param )
234  {
235  description_param_ = description_param;
236 
237  propertyChanged(robot_description_property_);
238 
239  if ( isEnabled() )
240  {
241  load();
242  unsubscribe();
243  subscribe();
244  causeRender();
245  }
246  }
247 
248  void EffortDisplay::setAllEnabled(bool enabled)
249  {
250  all_enabled_ = enabled;
251 
252  M_JointInfo::iterator it = joints_.begin();
253  M_JointInfo::iterator end = joints_.end();
254  for (; it != end; ++it)
255  {
256  JointInfo* joint = it->second;
257 
258  setJointEnabled(joint, enabled);
259  }
260 
261  propertyChanged(all_enabled_property_);
262  }
263 
264 #endif
265  // This is our callback to handle an incoming message.
266  void EffortDisplay::processMessage( const sensor_msgs::JointState::ConstPtr& msg )
267  {
268  // Robot model might not be loaded already
269  if (!robot_model_)
270  {
271  return;
272  }
273  // We are keeping a circular buffer of visual pointers. This gets
274  // the next one, or creates and stores it if the buffer is not full
276  if (visuals_.full())
277  {
278  visual = visuals_.front();
279  }
280  else
281  {
282  visual.reset(new EffortVisual(context_->getSceneManager(), scene_node_, robot_model_));
283  }
284 
285  V_string joints;
286  int joint_num = msg->name.size();
287  if (joint_num != msg->effort.size())
288  {
289  std::string tmp_error = "Received a joint state msg with different joint names and efforts size!";
290  ROS_ERROR("%s", tmp_error.c_str());
291  setStatus(rviz::StatusProperty::Error, "TOPIC", QString::fromStdString(tmp_error));
292  return;
293  }
294  for (int i = 0; i < joint_num; ++i)
295  {
296  std::string joint_name = msg->name[i];
297  JointInfo* joint_info = getJointInfo(joint_name);
298  if ( !joint_info ) continue; // skip joints..
299 
300  // set effort
301  joint_info->setEffort(msg->effort[i]);
302 
303  // update effort property ???
304  if ((ros::Time::now() - joint_info->last_update_) > ros::Duration(0.2))
305  {
306  joint_info->last_update_ = ros::Time::now();
307  }
308 
309  const urdf::Joint* joint = robot_model_->getJoint(joint_name).get();
310  int joint_type = joint->type;
311  if ( joint_type == urdf::Joint::REVOLUTE )
312  {
313  // we expects that parent_link_name equals to frame_id.
314  std::string parent_link_name = joint->child_link_name;
315  Ogre::Quaternion orientation;
316  Ogre::Vector3 position;
317 
318  // Here we call the rviz::FrameManager to get the transform from the
319  // fixed frame to the frame in the header of this Effort message. If
320  // it fails, we can't do anything else so we return.
321  if( !context_->getFrameManager()->getTransform( parent_link_name,
322  ros::Time(),
323  //msg->header.stamp, // ???
324  position, orientation ))
325  {
326  ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
327  parent_link_name.c_str(), qPrintable( fixed_frame_) );
328  continue;
329  }
330 ;
331  tf::Vector3 axis_joint(joint->axis.x, joint->axis.y, joint->axis.z);
332  tf::Vector3 axis_z(0,0,1);
333  tf::Quaternion axis_rotation(tf::tfCross(axis_joint, axis_z), tf::tfAngle(axis_joint, axis_z));
334  if ( std::isnan(axis_rotation.x()) ||
335  std::isnan(axis_rotation.y()) ||
336  std::isnan(axis_rotation.z()) ) axis_rotation = tf::Quaternion::getIdentity();
337 
338  tf::Quaternion axis_orientation(orientation.x, orientation.y, orientation.z, orientation.w);
339  tf::Quaternion axis_rot = axis_orientation * axis_rotation;
340  Ogre::Quaternion joint_orientation(Ogre::Real(axis_rot.w()), Ogre::Real(axis_rot.x()), Ogre::Real(axis_rot.y()), Ogre::Real(axis_rot.z()));
341  visual->setFramePosition( joint_name, position );
342  visual->setFrameOrientation( joint_name, joint_orientation );
343  visual->setFrameEnabled( joint_name, joint_info->getEnabled() );
344  }
345  }
346 
347 
348  // Now set or update the contents of the chosen visual.
349  float scale = scale_property_->getFloat();
350  float width = width_property_->getFloat();
351  visual->setWidth( width );
352  visual->setScale( scale );
353  visual->setMessage( msg );
354 
355  visuals_.push_back(visual);
356  }
357 
358 } // end namespace rviz
359 
360 // Tell pluginlib about this class. It is important to do this in
361 // global scope, outside our package's namespace.
364 
365 
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
#define NULL
Definition: global.h:37
void setEffort(double e)
static int limit(int i)
Definition: parse_color.cpp:35
virtual void reset()
Called to tell the display to clear its state.
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
std::string name_
ros::Time last_update_
JointInfo(const std::string name, rviz::Property *parent_category)
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:38
void setMaxEffort(double m)
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
void subscribe()
JointInfo * getJointInfo(const std::string &joint)
JointInfo * createJoint(const std::string &joint)
void processMessage(const sensor_msgs::JointState::ConstPtr &msg)
Implement this to process the contents of a message.
static const Quaternion & getIdentity()
TFSIMD_FORCE_INLINE Vector3 tfCross(const Vector3 &v1, const Vector3 &v2)
rviz::FloatProperty * max_effort_property_
virtual void onInitialize()
Override this function to do subclass-specific initialization.
std::vector< std::string > V_string
TFSIMD_FORCE_INLINE tfScalar tfAngle(const Vector3 &v1, const Vector3 &v2)
Property specialized for string values.
rviz::FloatProperty * effort_property_
rviz::Property * category_
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
Definition: property.cpp:145
static Time now()
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:397
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
bool getEnabled() const
#define ROS_DEBUG(...)


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