1 #include <OgreSceneNode.h> 2 #include <OgreSceneManager.h> 12 #include <boost/foreach.hpp> 64 M_JointInfo::iterator it = joints_.find( joint );
65 if ( it == joints_.end() )
76 joints_.insert( std::make_pair( joint, info ) );
85 "0 is fully transparent, 1.0 is fully opaque.",
86 this, SLOT( updateColorAndAlpha() ));
90 "Width to drow effort circle",
91 this, SLOT( updateColorAndAlpha() ));
95 "Scale to drow effort circle",
96 this, SLOT( updateColorAndAlpha() ));
98 history_length_property_ =
100 "Number of prior measurements to display.",
101 this, SLOT( updateHistoryLength() ));
102 history_length_property_->setMin( 1 );
103 history_length_property_->setMax( 100000 );
106 robot_description_property_ =
108 "Name of the parameter to search for to load the robot description.",
109 this, SLOT( updateRobotDescription() ) );
118 MFDClass::onInitialize();
119 updateHistoryLength();
137 robot_description_.clear();
143 float width = width_property_->getFloat();
144 float scale = scale_property_->getFloat();
146 for(
size_t i = 0; i < visuals_.size(); i++ )
148 visuals_[ i ]->setWidth( width );
149 visuals_[ i ]->setScale( scale );
158 context_->queueRender();
165 visuals_.rset_capacity(history_length_property_->getInt());
172 if (!update_nh_.getParam( robot_description_property_->getStdString(), content) ) {
174 if( update_nh_.searchParam( robot_description_property_->getStdString(), loc ))
176 update_nh_.getParam( loc, content );
182 "Parameter [" + robot_description_property_->getString()
183 +
"] does not exist, and was not found by searchParam()" );
188 if( content.empty() )
195 if( content == robot_description_ )
200 robot_description_ = content;
204 if (!robot_model_->initString(content))
206 ROS_ERROR(
"Unable to parse URDF description!");
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);
233 void EffortDisplay::setRobotDescription(
const std::string& description_param )
235 description_param_ = description_param;
237 propertyChanged(robot_description_property_);
248 void EffortDisplay::setAllEnabled(
bool enabled)
250 all_enabled_ = enabled;
252 M_JointInfo::iterator it = joints_.begin();
253 M_JointInfo::iterator end = joints_.end();
254 for (; it != end; ++it)
258 setJointEnabled(joint, enabled);
261 propertyChanged(all_enabled_property_);
278 visual = visuals_.front();
282 visual.reset(
new EffortVisual(context_->getSceneManager(), scene_node_, robot_model_));
286 int joint_num = msg->name.size();
287 if (joint_num != msg->effort.size())
289 std::string tmp_error =
"Received a joint state msg with different joint names and efforts size!";
294 for (
int i = 0; i < joint_num; ++i)
296 std::string joint_name = msg->name[i];
297 JointInfo* joint_info = getJointInfo(joint_name);
298 if ( !joint_info )
continue;
309 const urdf::Joint* joint = robot_model_->getJoint(joint_name).get();
310 int joint_type = joint->type;
311 if ( joint_type == urdf::Joint::REVOLUTE )
314 std::string parent_link_name = joint->child_link_name;
315 Ogre::Quaternion orientation;
316 Ogre::Vector3 position;
321 if( !context_->getFrameManager()->getTransform( parent_link_name,
324 position, orientation ))
326 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
327 parent_link_name.c_str(), qPrintable( fixed_frame_) );
331 tf::Vector3 axis_joint(joint->axis.x, joint->axis.y, joint->axis.z);
334 if ( std::isnan(axis_rotation.x()) ||
335 std::isnan(axis_rotation.y()) ||
338 tf::Quaternion axis_orientation(orientation.x, orientation.y, orientation.z, orientation.w);
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() );
349 float scale = scale_property_->getFloat();
350 float width = width_property_->getFloat();
351 visual->setWidth( width );
352 visual->setScale( scale );
353 visual->setMessage( msg );
355 visuals_.push_back(visual);
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
void updateRobotDescription()
void updateColorAndAlpha()
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...
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.
void setMaxEffort(double m)
void updateHistoryLength()
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
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...
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)