void GridCellsDisplay::setColor(const Ogre::ColourValue& color) { this->color = color; processMessage(current_message_); causeRender(); }
void LaserScanVisualizer::updateCloud() { { RenderAutoLock render_lock( this ); cloud_->clear(); if ( !points_.empty() ) { DV_Point::iterator it = points_.begin(); DV_Point::iterator end = points_.end(); for ( ; it != end; ++it ) { V_Point& points = *it; if ( !points.empty() ) { cloud_->addPoints( &points.front(), points.size() ); } } } } causeRender(); }
void PathDisplay::setColor(const Ogre::ColourValue& color) { color_ = color; processMessage(current_message_); causeRender(); }
void CovarianceDisplay::setScale (float scale) { scale_ = scale; propertyChanged (scale_property_); updateColorAndAlphaAndScale (); causeRender (); }
void CovarianceDisplay::setAlpha (float alpha) { alpha_ = alpha; propertyChanged (alpha_property_); updateColorAndAlphaAndScale (); causeRender (); }
void CovarianceDisplay::setColor (const rviz::Color& color) { color_ = color; propertyChanged (color_property_); updateColorAndAlphaAndScale (); causeRender (); }
void AmbientSoundDisplay::setColor( const rviz::Color& color )/*{{{*/ { color_ = color; propertyChanged( color_property_ ); updateColorAndAlpha(); causeRender(); }/*}}}*/
void AmbientSoundDisplay::setGrad( float grad )/*{{{*/ { grad_ = grad; propertyChanged( grad_property_ ); updateColorAndAlpha(); causeRender(); }/*}}}*/
void AmbientSoundDisplay::setBias( float bias )/*{{{*/ { bias_ = bias; propertyChanged( bias_property_ ); updateColorAndAlpha(); causeRender(); }/*}}}*/
void AmbientSoundDisplay::setScale( float scale )/*{{{*/ { scale_ = scale; propertyChanged( scale_property_ ); updateColorAndAlpha(); causeRender(); }
/*! All ROS interfaces are shutdown and then restarted after the topic name has been changed. By shutting down all interfaces, it simplifies the process */ void ImageMapDisplay::setImageStoreTopic(const std::string& topic){ unsubscribe(); clear(); imageStoreTopic = topic; subscribe(); propertyChanged(imageStoreTopicProperty); causeRender(); }
void CameraDisplaySave::setAlpha( float alpha ) { alpha_ = alpha; propertyChanged(alpha_property_); causeRender(); }
void AmbientSoundDisplay::setAlpha( float alpha )/*{{{*/ { alpha_ = alpha; propertyChanged( alpha_property_ ); updateColorAndAlpha(); causeRender(); }/*}}}*/
void AmbientSoundDisplay::setWidth( float width )/*{{{*/ { width_ = width; propertyChanged( width_property_ ); updateColorAndAlpha(); causeRender(); }/*}}}*/
void NXTUltrasonicDisplay::setColor( const rviz::Color& color ) { color_ = color; propertyChanged(color_property_); processMessage(current_message_); causeRender(); }
void NXTUltrasonicDisplay::setAlpha( float alpha ) { alpha_ = alpha; propertyChanged(alpha_property_); processMessage(current_message_); causeRender(); }
void PointCloudDisplay::setBillboardSize( float size ) { { RenderAutoLock renderLock( this ); billboard_size_ = size; cloud_->setBillboardDimensions( size, size ); } causeRender(); if ( billboard_size_property_ ) { billboard_size_property_->changed(); } causeRender(); }
void TFDisplay::updateFrames() { typedef std::vector<std::string> V_string; V_string frames; tf_->getFrameStrings( frames ); S_FrameInfo current_frames; { V_string::iterator it = frames.begin(); V_string::iterator end = frames.end(); for ( ; it != end; ++it ) { const std::string& frame = *it; if ( frame.empty() ) { continue; } FrameInfo* info = getFrameInfo( frame ); if (!info) { info = createFrame(frame); } else { updateFrame(info); } current_frames.insert( info ); } } { S_FrameInfo to_delete; M_FrameInfo::iterator frame_it = frames_.begin(); M_FrameInfo::iterator frame_end = frames_.end(); for ( ; frame_it != frame_end; ++frame_it ) { if ( current_frames.find( frame_it->second ) == current_frames.end() ) { to_delete.insert( frame_it->second ); } } S_FrameInfo::iterator delete_it = to_delete.begin(); S_FrameInfo::iterator delete_end = to_delete.end(); for ( ; delete_it != delete_end; ++delete_it ) { deleteFrame( *delete_it ); } } causeRender(); }
/*! All ROS interfaces are shutdown and then restarted after the topic name has been changed. By shutting down all interfaces, it simplifies the process */ void ImageMapDisplay::setRelPoseTopic(const std::string& topic){ unsubscribe(); clear(); relPoseTopic = topic; subscribe(); // Broadcast the fact that the variable has changed. propertyChanged(relPoseTopicProperty); // Make sure rviz renders the next time it gets a chance. causeRender(); }
void GridCellsDisplay::setTopic( const std::string& topic ) { unsubscribe(); this->topic = topic; subscribe(); causeRender(); }
void PlanningDisplay::setVisualVisible( bool visible ) { robot_->setVisualVisible( visible ); if ( visual_enabled_property_ ) { visual_enabled_property_->changed(); } causeRender(); }
void MarkerVisualizer::processDelete( const std_msgs::VisualizationMarker& message ) { M_IDToMarker::iterator it = markers_.find( message.id ); if ( it != markers_.end() ) { delete it->second.object_; markers_.erase( it ); } causeRender(); }
void PointCloud2Display::setTopic( const std::string& topic ) { unsubscribe(); topic_ = topic; reset(); subscribe(); propertyChanged(topic_property_); causeRender(); }
void PointCloudDisplay::setStyle( int style ) { ROS_ASSERT( style < StyleCount ); { RenderAutoLock renderLock( this ); style_ = style; cloud_->setUsePoints( style == Points ); } causeRender(); if ( style_property_ ) { style_property_->changed(); } causeRender(); }
void PointCloudDisplay::setColor( const Color& color ) { color_ = color; if ( color_property_ ) { color_property_->changed(); } causeRender(); }
void CovarianceDisplay::setTopic (const std::string& topic) { unsubscribe (); clear (); topic_ = topic; subscribe (); propertyChanged (topic_property_); causeRender (); }
void PlanningDisplay::setCollisionVisible( bool visible ) { robot_->setCollisionVisible( visible ); if ( collision_enabled_property_ ) { collision_enabled_property_->changed(); } causeRender(); }
void PlanningDisplay::setStateDisplayTime( float time ) { state_display_time_ = time; if ( state_display_time_property_ ) { state_display_time_property_->changed(); } causeRender(); }
void RobotModelDisplay::setUpdateRate( float rate ) { update_rate_ = rate; if ( update_rate_property_ ) { update_rate_property_->changed(); } causeRender(); }
void NXTUltrasonicDisplay::setTopic( const std::string& topic ) { unsubscribe(); topic_ = topic; subscribe(); propertyChanged(topic_property_); causeRender(); }