EffortDisplay::EffortDisplay()
    {
	alpha_property_ =
	    new rviz::FloatProperty( "Alpha", 1.0,
                                     "0 is fully transparent, 1.0 is fully opaque.",
                                     this, SLOT( updateColorAndAlpha() ));

	width_property_ =
	    new rviz::FloatProperty( "Width", 0.02,
                                     "Width to drow effort circle",
                                     this, SLOT( updateColorAndAlpha() ));

	scale_property_ =
	    new rviz::FloatProperty( "Scale", 1.0,
                                     "Scale to drow effort circle",
                                     this, SLOT( updateColorAndAlpha() ));

	history_length_property_ =
	    new rviz::IntProperty( "History Length", 1,
                                   "Number of prior measurements to display.",
                                   this, SLOT( updateHistoryLength() ));
        history_length_property_->setMin( 1 );
        history_length_property_->setMax( 100000 );


        robot_description_property_ =
            new rviz::StringProperty( "Robot Description", "robot_description",
                                      "Name of the parameter to search for to load the robot description.",
                                      this, SLOT( updateRobotDescription() ) );


        joints_category_ =
            new rviz::Property("Joints", QVariant(), "", this);
    }
// BEGIN_TUTORIAL
// The constructor must have no arguments, so we can't give the
// constructor the parameters it needs to fully initialize.
  OrkObjectDisplay::OrkObjectDisplay()
  {
    color_property_ = new rviz::ColorProperty("Color", QColor(204, 51, 204), "Color to draw the acceleration arrows.",
                                              this, SLOT(updateColorAndAlpha()));

    alpha_property_ = new rviz::FloatProperty("Alpha", 1.0, "0 is fully transparent, 1.0 is fully opaque.", this,
                                              SLOT(updateColorAndAlpha()));

    history_length_property_ = new rviz::IntProperty("History Length", 1, "Number of prior measurements to display.",
                                                     this, SLOT(updateHistoryLength()));
    history_length_property_->setMin(1);
    history_length_property_->setMax(100000);
  }
  MoveItCollisionMapDisplay::MoveItCollisionMapDisplay() {
    color_property_ = new rviz::ColorProperty("Color", QColor(204, 51, 204),
					      "Base color to draw the cubes.",
					      this, SLOT(updateColorAndAlpha()));
    
    alpha_property_ = new rviz::FloatProperty("Alpha", 1.0,
					      "0 is fully transparent, 1.0 is fully opaque.",
					      this, SLOT(updateColorAndAlpha()));
    
    history_length_property_ = new rviz::IntProperty("History Length", 5000,
						     "Number of cubes to display at the same time.",
						     this, SLOT(updateHistoryLength()));
    history_length_property_->setMin(1);
    history_length_property_->setMax(100000);
  }
    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();
 }
 void AmbientSoundDisplay::setWidth( float width )/*{{{*/
 {
     width_ = width;
     
     propertyChanged( width_property_ );
     updateColorAndAlpha();
     causeRender();
 }/*}}}*/
    void AmbientSoundDisplay::setAlpha( float alpha )/*{{{*/
    {
        alpha_ = alpha;

        propertyChanged( alpha_property_ );
        updateColorAndAlpha();
        causeRender();
    }/*}}}*/
    PointStampedDisplay::PointStampedDisplay()
    {
	color_property_ =
	    new rviz::ColorProperty( "Color", QColor(204, 41, 204),
                                     "Color of a point",
                                     this, SLOT( updateColorAndAlpha() ));

	alpha_property_ =
	    new rviz::FloatProperty( "Alpha", 1.0,
                                     "0 is fully transparent, 1.0 is fully opaque.",
                                     this, SLOT( updateColorAndAlpha() ));

	radius_property_ =
	    new rviz::FloatProperty( "Radius", 0.2,
                                     "Radius of a point",
                                     this, SLOT( updateColorAndAlpha() ));

	history_length_property_ =
	    new rviz::IntProperty( "History Length", 1,
                                   "Number of prior measurements to display.",
                                   this, SLOT( updateHistoryLength() ));
        history_length_property_->setMin( 1 );
        history_length_property_->setMax( 100000 );
    }