コード例 #1
0
ファイル: oculus_display.cpp プロジェクト: rahulraw/adVentuRe
void OculusDisplay::onEnable()
{
  if ( oculus_ )
  {
     return;
  }

  oculus_.reset( new Oculus() );
  oculus_->setupOculus();

  if ( !oculus_->isOculusReady() )
  {
    oculus_.reset();
    setStatusStd( rviz::StatusProperty::Error, "Oculus", "No Oculus device found!" );
    return;
  }

  setStatusStd( rviz::StatusProperty::Ok, "Oculus", "Oculus is ready." );

  Ogre::RenderWindow *window = render_widget_->getRenderWindow();
  oculus_->setupOgre( scene_manager_, window, scene_node_ );

  render_widget_->setVisible( oculus_->isOculusReady() );

  onScreenCountChanged( QApplication::desktop()->numScreens() );
  onFullScreenChanged();
  onPredictionDtChanged();
}
void InteractiveMarkerDisplay::updatePoses(
    const std::string& server_id,
    const std::vector<visualization_msgs::InteractiveMarkerPose>& marker_poses )
{
  M_StringToIMPtr& im_map = getImMap( server_id );

  for ( size_t i=0; i<marker_poses.size(); i++ )
  {
    const visualization_msgs::InteractiveMarkerPose& marker_pose = marker_poses[i];

    if ( !validateFloats( marker_pose.pose ) )
    {
      setStatusStd( StatusProperty::Error, marker_pose.name, "Pose message contains invalid floats!" );
      return;
    }

    std::map< std::string, IMPtr >::iterator int_marker_entry = im_map.find( marker_pose.name );

    if ( int_marker_entry != im_map.end() )
    {
      int_marker_entry->second->processMessage( marker_pose );
    }
    else
    {
      setStatusStd( StatusProperty::Error, marker_pose.name, "Pose received for non-existing marker '" + marker_pose.name );
      unsubscribe();
      return;
    }
  }
}
コード例 #3
0
void MarkerDisplay::setMarkerStatus(MarkerID id, StatusLevel level, const std::string& text)
{
  std::stringstream ss;
  ss << id.first << "/" << id.second;
  std::string marker_name = ss.str();
  setStatusStd(level, marker_name, text);
}
void InteractiveMarkerDisplay::statusCb(
    interactive_markers::InteractiveMarkerClient::StatusT status,
    const std::string& server_id,
    const std::string& msg )
{
  setStatusStd( static_cast<StatusProperty::Level>(status), server_id, msg );
}
void InteractiveMarkerDisplay::updateTopic()
{
  unsubscribe();

  std::string update_topic = marker_update_topic_property_->getTopicStd();

  size_t idx = update_topic.find( "/update" );
  if ( idx != std::string::npos )
  {
    topic_ns_ = update_topic.substr( 0, idx );
    subscribe();
  }
  else
  {
    setStatusStd( StatusProperty::Error, "Topic", "Invalid topic name: " + update_topic );
  }

}
void InteractiveMarkerDisplay::updateMarkers(
    const std::string& server_id,
    const std::vector<visualization_msgs::InteractiveMarker>& markers
    )
{
  M_StringToIMPtr& im_map = getImMap( server_id );

  for ( size_t i=0; i<markers.size(); i++ )
  {
    const visualization_msgs::InteractiveMarker& marker = markers[i];

    if ( !validateFloats( marker ) )
    {
      setStatusStd( StatusProperty::Error, marker.name, "Marker contains invalid floats!" );
      //setStatusStd( StatusProperty::Error, "General", "Marker " + marker.name + " contains invalid floats!" );
      continue;
    }
    ROS_DEBUG("Processing interactive marker '%s'. %d", marker.name.c_str(), (int)marker.controls.size() );

    std::map< std::string, IMPtr >::iterator int_marker_entry = im_map.find( marker.name );

    if ( int_marker_entry == im_map.end() )
    {
      int_marker_entry = im_map.insert( std::make_pair(marker.name, IMPtr ( new InteractiveMarker(this, context_, topic_ns_, client_id_) ) ) ).first;
    }

    if ( int_marker_entry->second->processMessage( marker ) )
    {
      int_marker_entry->second->setShowAxes( show_axes_property_->getBool() );
      int_marker_entry->second->setShowDescription( show_descriptions_property_->getBool() );
    }
    else
    {
      unsubscribe();
      return;
    }
  }
}