Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 #include <moveit/trajectory_rviz_plugin/trajectory_display.h>
00040 #include <rviz/properties/string_property.h>
00041 
00042 namespace moveit_rviz_plugin
00043 {
00044 TrajectoryDisplay::TrajectoryDisplay() : Display()
00045 {
00046   
00047   
00048   robot_description_property_ = new rviz::StringProperty(
00049       "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded",
00050       this, SLOT(changedRobotDescription()), this);
00051 
00052   trajectory_visual_.reset(new TrajectoryVisualization(this, this));
00053 }
00054 
00055 TrajectoryDisplay::~TrajectoryDisplay()
00056 {
00057 }
00058 
00059 void TrajectoryDisplay::onInitialize()
00060 {
00061   Display::onInitialize();
00062 
00063   trajectory_visual_->onInitialize(scene_node_, context_, update_nh_);
00064 }
00065 
00066 void TrajectoryDisplay::loadRobotModel()
00067 {
00068   rdf_loader_.reset(new rdf_loader::RDFLoader(robot_description_property_->getStdString()));
00069 
00070   if (!rdf_loader_->getURDF())
00071   {
00072     ROS_DEBUG_STREAM_NAMED("trajectory_display", "Unable to load robot model from parameter "
00073                                                      << robot_description_property_->getStdString());
00074     return;
00075   }
00076 
00077   const boost::shared_ptr<srdf::Model>& srdf =
00078       rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : boost::shared_ptr<srdf::Model>(new srdf::Model());
00079   robot_model_.reset(new robot_model::RobotModel(rdf_loader_->getURDF(), srdf));
00080 
00081   
00082   trajectory_visual_->onRobotModelLoaded(robot_model_);
00083 }
00084 
00085 void TrajectoryDisplay::reset()
00086 {
00087   Display::reset();
00088   loadRobotModel();
00089   trajectory_visual_->reset();
00090 }
00091 
00092 void TrajectoryDisplay::onEnable()
00093 {
00094   Display::onEnable();
00095   loadRobotModel();
00096   trajectory_visual_->onEnable();
00097 }
00098 
00099 void TrajectoryDisplay::onDisable()
00100 {
00101   Display::onDisable();
00102   trajectory_visual_->onDisable();
00103 }
00104 
00105 void TrajectoryDisplay::update(float wall_dt, float ros_dt)
00106 {
00107   Display::update(wall_dt, ros_dt);
00108   trajectory_visual_->update(wall_dt, ros_dt);
00109 }
00110 
00111 void TrajectoryDisplay::setName(const QString& name)
00112 {
00113   BoolProperty::setName(name);
00114   trajectory_visual_->setName(name);
00115 }
00116 
00117 void TrajectoryDisplay::changedRobotDescription()
00118 {
00119   loadRobotModel();
00120 
00121   if (isEnabled())
00122     reset();
00123 }
00124 
00125 }