osgEarth 2.1.1
Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes

osgEarth::Features::ExtrudeGeometryFilter Class Reference

Inheritance diagram for osgEarth::Features::ExtrudeGeometryFilter:
Collaboration diagram for osgEarth::Features::ExtrudeGeometryFilter:

List of all members.

Classes

struct  HeightCallback

Public Member Functions

 ExtrudeGeometryFilter ()
void setStyle (const Style &style)
osg::Node * push (FeatureList &input, FilterContext &context)
void setWallAngleThreshold (float angle_deg)
void setFeatureNameExpr (const StringExpression &expr)
const StringExpressiongetFeatureNameExpr () const

Protected Types

typedef std::map
< osg::StateSet
*, osg::ref_ptr< osg::Geode > > 
SortedGeodeMap

Protected Member Functions

void reset (const FilterContext &context)
void addDrawable (osg::Drawable *drawable, osg::StateSet *stateSet, const std::string &name)
bool process (FeatureList &input, FilterContext &context)
bool extrudeGeometry (const Geometry *input, double height, double offset, bool uniformHeight, osg::Geometry *walls, osg::Geometry *top_cap, osg::Geometry *bottom_cap, osg::Geometry *outline, const osg::Vec4 &wallColor, const osg::Vec4 &roofColor, const osg::Vec4 &outlineColor, const SkinResource *wallSkin, const SkinResource *roofSkin, FilterContext &cx)

Protected Attributes

SortedGeodeMap _geodes
osg::ref_ptr< osg::StateSet > _noTextureStateSet
optional< double > _maxAngle_deg
optional< bool > _mergeGeometry
float _wallAngleThresh_deg
float _cosWallAngleThresh
StringExpression _featureNameExpr
osg::ref_ptr< HeightCallback_heightCallback
optional< NumericExpression_heightOffsetExpr
optional< NumericExpression_heightExpr
Style _style
bool _styleDirty
osg::ref_ptr< const
ExtrusionSymbol
_extrusionSymbol
osg::ref_ptr< const SkinSymbol_wallSkinSymbol
osg::ref_ptr< const PolygonSymbol_wallPolygonSymbol
osg::ref_ptr< const SkinSymbol_roofSkinSymbol
osg::ref_ptr< const PolygonSymbol_roofPolygonSymbol
osg::ref_ptr< const LineSymbol_outlineSymbol
osg::ref_ptr< ResourceLibrary_wallResLib
osg::ref_ptr< ResourceLibrary_roofResLib

Detailed Description

Extrudes footprint geometry into 3D geometry

Definition at line 38 of file ExtrudeGeometryFilter.


Member Typedef Documentation

typedef std::map<osg::StateSet*, osg::ref_ptr<osg::Geode> > osgEarth::Features::ExtrudeGeometryFilter::SortedGeodeMap [protected]

Definition at line 79 of file ExtrudeGeometryFilter.


Constructor & Destructor Documentation

ExtrudeGeometryFilter::ExtrudeGeometryFilter ( )

Constructs a new filter that will extrude footprints

Definition at line 72 of file ExtrudeGeometryFilter.cpp.

                                             :
_maxAngle_deg       ( 5.0 ),
_mergeGeometry      ( true ),
_wallAngleThresh_deg( 60.0 ),
_styleDirty         ( true )
{
    //NOP
}

Member Function Documentation

void ExtrudeGeometryFilter::addDrawable ( osg::Drawable *  drawable,
osg::StateSet *  stateSet,
const std::string &  name 
) [protected]

Definition at line 593 of file ExtrudeGeometryFilter.cpp.

{
    // find the geode for the active stateset, creating a new one if necessary. NULL is a 
    // valid key as well.
    osg::Geode* geode = _geodes[stateSet].get();
    if ( !geode )
    {
        geode = new osg::Geode();
        geode->setStateSet( stateSet );
        _geodes[stateSet] = geode;
    }

    geode->addDrawable( drawable );

    if ( !name.empty() )
    {
        drawable->setName( name );
    }
}

Here is the caller graph for this function:

bool ExtrudeGeometryFilter::extrudeGeometry ( const Geometry input,
double  height,
double  offset,
bool  uniformHeight,
osg::Geometry *  walls,
osg::Geometry *  top_cap,
osg::Geometry *  bottom_cap,
osg::Geometry *  outline,
const osg::Vec4 &  wallColor,
const osg::Vec4 &  roofColor,
const osg::Vec4 &  outlineColor,
const SkinResource wallSkin,
const SkinResource roofSkin,
FilterContext cx 
) [protected]

Definition at line 176 of file ExtrudeGeometryFilter.cpp.

{
    //todo: establish reference frame for going to geocentric. This will ultimately
    // passed in to the function.
    const SpatialReference* srs = cx.extent()->getSRS();

    // whether to convert the final geometry to localized ECEF
    bool makeECEF = cx.getSession()->getMapInfo().isGeocentric();

    bool made_geom = false;

    double tex_width_m   = wallSkin ? *wallSkin->imageWidth() : 1.0;
    double tex_height_m  = wallSkin ? *wallSkin->imageHeight() : 1.0;
    bool   tex_repeats_y = wallSkin ? *wallSkin->isTiled() : false;
    bool   useColor      = !wallSkin || wallSkin->texEnvMode() != osg::TexEnv::DECAL;

    bool isPolygon = input->getComponentType() == Geometry::TYPE_POLYGON;

    unsigned pointCount = input->getTotalPointCount();
    
    // If we are extruding a polygon, and applying a wall texture, we need an extra
    // point in the geometry in order to close the polygon and generate a unique
    // texture coordinate for that final point.
    bool isSkinnedPolygon = isPolygon && wallSkin != 0L;

    // Total number of verts. Add 2 to close a polygon (necessary so the first and last
    // points can have unique texture coordinates)
    unsigned numWallVerts = 2 * pointCount + (isSkinnedPolygon? (2 * input->getNumGeometries()) : 0);

    // create all the OSG geometry components
    osg::Vec3Array* verts = new osg::Vec3Array( numWallVerts );
    walls->setVertexArray( verts );

    osg::Vec2Array* wallTexcoords = 0L;
    if ( wallSkin )
    { 
        wallTexcoords = new osg::Vec2Array( numWallVerts );
        walls->setTexCoordArray( 0, wallTexcoords );
    }

    if ( useColor )
    {
        // per-vertex colors are necessary if we are going to use the MeshConsolidator -gw
        osg::Vec4Array* colors = new osg::Vec4Array();
        colors->reserve( numWallVerts );
        colors->assign( numWallVerts, wallColor );
        walls->setColorArray( colors );
        walls->setColorBinding( osg::Geometry::BIND_PER_VERTEX );
        //osg::Vec4Array* colors = new osg::Vec4Array( 1 );
        //(*colors)[0] = wallColor;
        //walls->setColorArray( colors );
        //walls->setColorBinding( osg::Geometry::BIND_OVERALL );
    }

    // set up rooftop tessellation and texturing, if necessary:
    osg::Vec3Array* roofVerts     = 0L;
    osg::Vec2Array* roofTexcoords = 0L;
    float           roofRotation  = 0.0f;
    Bounds          roofBounds;
    float           sinR, cosR;
    double          roofTexSpanX, roofTexSpanY;
    osg::ref_ptr<const SpatialReference> roofProjSRS;

    if ( roof )
    {
        roofVerts = new osg::Vec3Array( pointCount );
        roof->setVertexArray( roofVerts );

        // per-vertex colors are necessary if we are going to use the MeshConsolidator -gw
        osg::Vec4Array* roofColors = new osg::Vec4Array();
        roofColors->reserve( pointCount );
        roofColors->assign( pointCount, roofColor );
        roof->setColorArray( roofColors );
        roof->setColorBinding( osg::Geometry::BIND_PER_VERTEX );
        //osg::Vec4Array* roofColors = new osg::Vec4Array( 1 );
        //(*roofColors)[0] = roofColor;
        //roof->setColorArray( roofColors );
        //roof->setColorBinding( osg::Geometry::BIND_OVERALL );

        if ( roofSkin )
        {
            roofTexcoords = new osg::Vec2Array( pointCount );
            roof->setTexCoordArray( 0, roofTexcoords );

            // Get the orientation of the geometry. This is a hueristic that will help 
            // us align the roof skin texture properly. TODO: make this optional? It makes
            // sense for buildings and such, but perhaps not for all extruded shapes.
            roofRotation = getApparentRotation( input );

            roofBounds = input->getBounds();

            // if our data is lat/long, we need to reproject the geometry and the bounds into a projected
            // coordinate system in order to properly generate tex coords.
            if ( srs->isGeographic() )
            {
                osg::Vec2d geogCenter = roofBounds.center2d();
                roofProjSRS = srs->createUTMFromLongitude( Angular(geogCenter.x()) );
                roofBounds.transform( srs, roofProjSRS.get() );
                osg::ref_ptr<Geometry> projectedInput = input->clone();
                srs->transformPoints( roofProjSRS.get(), projectedInput->asVector() );
                roofRotation = getApparentRotation( projectedInput.get() );
            }
            else
            {
                roofRotation = getApparentRotation( input );
            }
            
            sinR = sin(roofRotation);
            cosR = cos(roofRotation);

            if ( !roofSkin->isTiled().value() )
            {
                //note: doesn't really work
                roofTexSpanX = cosR*roofBounds.width() - sinR*roofBounds.height();
                roofTexSpanY = sinR*roofBounds.width() + cosR*roofBounds.height();
            }
            else
            {
                roofTexSpanX = roofSkin->imageWidth().isSet() ? *roofSkin->imageWidth() : roofSkin->imageHeight().isSet() ? *roofSkin->imageHeight() : 10.0;
                if ( roofTexSpanX <= 0.0 ) roofTexSpanX = 10.0;
                roofTexSpanY = roofSkin->imageHeight().isSet() ? *roofSkin->imageHeight() : roofSkin->imageWidth().isSet() ? *roofSkin->imageWidth() : 10.0;
                if ( roofTexSpanY <= 0.0 ) roofTexSpanY = 10.0;
            }
        }
    }

    osg::Vec3Array* baseVerts = NULL;
    if ( base )
    {
        baseVerts = new osg::Vec3Array( pointCount );
        base->setVertexArray( baseVerts );
    }

    osg::Vec3Array* outlineVerts = 0L;
    osg::Vec3Array* outlineNormals = 0L;
    if ( outline )
    {
        outlineVerts = new osg::Vec3Array( numWallVerts );
        outline->setVertexArray( outlineVerts );

        osg::Vec4Array* outlineColors = new osg::Vec4Array();
        outlineColors->reserve( numWallVerts );
        outlineColors->assign( numWallVerts, outlineColor );
        outline->setColorArray( outlineColors );
        outline->setColorBinding( osg::Geometry::BIND_PER_VERTEX );

        // cop out, just point all the outline normals up. fix this later.
        outlineNormals = new osg::Vec3Array();
        outlineNormals->reserve( numWallVerts );
        outlineNormals->assign( numWallVerts, osg::Vec3(0,0,1) );
        outline->setNormalArray( outlineNormals );
    }

    unsigned wallVertPtr    = 0;
    unsigned roofVertPtr    = 0;
    unsigned baseVertPtr    = 0;

    double     targetLen = -DBL_MAX;
    osg::Vec3d minLoc(DBL_MAX, DBL_MAX, DBL_MAX);
    double     minLoc_len = DBL_MAX;
    osg::Vec3d maxLoc(0,0,0);
    double     maxLoc_len = 0;

    // Initial pass over the geometry does two things:
    // 1: Calculate the minimum Z across all parts.
    // 2: Establish a "target length" for extrusion

    double absHeight = fabs(height);

    ConstGeometryIterator zfinder( input );
    while( zfinder.hasMore() )
    {
        const Geometry* geom = zfinder.next();
        for( Geometry::const_iterator m = geom->begin(); m != geom->end(); ++m )
        {
            osg::Vec3d m_point = *m;

            if ( m_point.z() + absHeight > targetLen )
                targetLen = m_point.z() + absHeight;

            if (m_point.z() < minLoc.z())
                minLoc = m_point;

            if (m_point.z() > maxLoc.z())
                maxLoc = m_point;
        }
    }

    // apply the height offsets
    height    -= heightOffset;
    targetLen -= heightOffset;

    // now generate the extruded geometry.
    ConstGeometryIterator iter( input );
    while( iter.hasMore() )
    {
        const Geometry* part = iter.next();

        double tex_height_m_adj = tex_height_m;

        unsigned wallPartPtr = wallVertPtr;
        unsigned roofPartPtr = roofVertPtr;
        unsigned basePartPtr = baseVertPtr;
        double   partLen     = 0.0;
        double   maxHeight   = 0.0;

        maxHeight = targetLen - minLoc.z();

        // Adjust the texture height so it is a multiple of the maximum height
        double div = osg::round(maxHeight / tex_height_m);
        if (div == 0) div = 1; //Prevent divide by zero
        tex_height_m_adj = maxHeight / div;

        osg::DrawElementsUInt* idx = new osg::DrawElementsUInt( GL_TRIANGLES );

        for( Geometry::const_iterator m = part->begin(); m != part->end(); ++m )
        {
            osg::Vec3d basePt = *m;
            osg::Vec3d roofPt;

            if ( height >= 0 )
            {
                if ( flatten )
                    roofPt.set( basePt.x(), basePt.y(), targetLen );
                else
                    roofPt.set( basePt.x(), basePt.y(), basePt.z() + height );
            }
            else // height < 0
            {
                roofPt = *m;
                basePt.z() += height;
            }

            // add to the approprate vertex lists:
            int p = wallVertPtr;

            // figure out the rooftop texture coordinates before doing any
            // transformations:
            if ( roofSkin )
            {
                double xr, yr;

                if ( srs->isGeographic() )
                {
                    osg::Vec3d projRoofPt;
                    srs->transform( roofPt, roofProjSRS.get(), projRoofPt );
                    xr = (projRoofPt.x() - roofBounds.xMin());
                    yr = (projRoofPt.y() - roofBounds.yMin());
                }
                else
                {
                    xr = (roofPt.x() - roofBounds.xMin());
                    yr = (roofPt.y() - roofBounds.yMin());
                }

                float u = (cosR*xr - sinR*yr) / roofTexSpanX;
                float v = (sinR*xr + cosR*yr) / roofTexSpanY;

                (*roofTexcoords)[roofVertPtr].set( u, v );
            }            

            if ( makeECEF )
            {
                ECEF::transformAndLocalize( basePt, basePt, srs, _world2local );
                ECEF::transformAndLocalize( roofPt, roofPt, srs, _world2local );
            }

            if ( base )
                (*baseVerts)[baseVertPtr] = basePt;
            if ( roof )
                (*roofVerts)[roofVertPtr] = roofPt;

            baseVertPtr++;
            roofVertPtr++;

            (*verts)[p] = roofPt;
            (*verts)[p+1] = basePt;

            if ( outline )
            {
                (*outlineVerts)[p] = roofPt;
                (*outlineVerts)[p+1] = basePt;
            }
            
            partLen += wallVertPtr > wallPartPtr ? ((*verts)[p] - (*verts)[p-2]).length() : 0.0;
            double h = tex_repeats_y ? -((*verts)[p] - (*verts)[p+1]).length() : -tex_height_m_adj;

            if ( wallSkin )
            {
                (*wallTexcoords)[p].set( partLen/tex_width_m, 0.0f );
                (*wallTexcoords)[p+1].set( partLen/tex_width_m, h/tex_height_m_adj );
            }

            // form the 2 triangles
            if ( (m+1) == part->end() )
            {
                if ( isPolygon )
                {
                    // end of the wall; loop around to close it off.
                    if ( isSkinnedPolygon )
                    {
                        // if we requested an extra geometry point, that means we are generating
                        // a polygon-closing line so we can have a unique texcoord for it. 
                        idx->push_back(wallVertPtr);
                        idx->push_back(wallVertPtr+1);
                        idx->push_back(wallVertPtr+2);

                        idx->push_back(wallVertPtr+1);
                        idx->push_back(wallVertPtr+3);
                        idx->push_back(wallVertPtr+2);

                        (*verts)[p+2] = (*verts)[wallPartPtr];
                        (*verts)[p+3] = (*verts)[wallPartPtr+1];

                        if ( wallSkin )
                        {
                            partLen += ((*verts)[p+2] - (*verts)[p]).length();
                            double h = tex_repeats_y ? -((*verts)[p+2] - (*verts)[p+3]).length() : -tex_height_m_adj;
                            (*wallTexcoords)[p+2].set( partLen/tex_width_m, 0.0f );
                            (*wallTexcoords)[p+3].set( partLen/tex_width_m, h/tex_height_m_adj );
                        }

                        wallVertPtr += 2;
                    }
                    else
                    {
                        // either not a poly, or no wall skin, so we can share the polygon-closing
                        // loop point.
                        idx->push_back(wallVertPtr); 
                        idx->push_back(wallVertPtr+1);
                        idx->push_back(wallPartPtr);

                        idx->push_back(wallVertPtr+1);
                        idx->push_back(wallPartPtr+1);
                        idx->push_back(wallPartPtr);
                    }
                }
                else
                {
                    //nop - no elements required at the end of a line
                }
            }
            else
            {
                idx->push_back(wallVertPtr); 
                idx->push_back(wallVertPtr+1);
                idx->push_back(wallVertPtr+2); 

                idx->push_back(wallVertPtr+1);
                idx->push_back(wallVertPtr+3);
                idx->push_back(wallVertPtr+2);
            }

            wallVertPtr += 2;
            made_geom = true;
        }

        walls->addPrimitiveSet( idx );

        if ( roof )
        {
            roof->addPrimitiveSet( new osg::DrawArrays(
                osg::PrimitiveSet::LINE_LOOP,
                roofPartPtr, roofVertPtr - roofPartPtr ) );
        }

        if ( base )
        {
            // reverse the base verts:
            int len = baseVertPtr - basePartPtr;
            for( int i=basePartPtr; i<len/2; i++ )
                std::swap( (*baseVerts)[i], (*baseVerts)[basePartPtr+(len-1)-i] );

            base->addPrimitiveSet( new osg::DrawArrays(
                osg::PrimitiveSet::LINE_LOOP,
                basePartPtr, baseVertPtr - basePartPtr ) );
        }

        if ( outline )
        {
            unsigned len = baseVertPtr - basePartPtr;

            GLenum roofLineMode = isPolygon ? GL_LINE_LOOP : GL_LINE_STRIP;
            osg::DrawElementsUInt* roofLine = new osg::DrawElementsUInt( roofLineMode );
            roofLine->reserveElements( len );
            for( unsigned i=0; i<len; ++i )
                roofLine->addElement( basePartPtr + i*2 );
            outline->addPrimitiveSet( roofLine );

            osg::DrawElementsUShort* wallLines = new osg::DrawElementsUShort( GL_LINES );
            wallLines->reserve( len*2 );
            for( unsigned i=0; i<len; ++i )
            {
                wallLines->push_back( basePartPtr + i*2 );
                wallLines->push_back( basePartPtr + i*2 + 1 );
            }
            outline->addPrimitiveSet( wallLines );
        }
    }

    return made_geom;
}

Here is the call graph for this function:

Here is the caller graph for this function:

const StringExpression& osgEarth::Features::ExtrudeGeometryFilter::getFeatureNameExpr ( ) const [inline]

Definition at line 73 of file ExtrudeGeometryFilter.

{ return _featureNameExpr; }
bool ExtrudeGeometryFilter::process ( FeatureList input,
FilterContext context 
) [protected]

Definition at line 614 of file ExtrudeGeometryFilter.cpp.

{
    // seed our random number generators
    Random wallSkinPRNG( _wallSkinSymbol.valid()? *_wallSkinSymbol->randomSeed() : 0, Random::METHOD_FAST );
    Random roofSkinPRNG( _roofSkinSymbol.valid()? *_roofSkinSymbol->randomSeed() : 0, Random::METHOD_FAST );

    for( FeatureList::iterator f = features.begin(); f != features.end(); ++f )
    {
        Feature* input = f->get();

        GeometryIterator iter( input->getGeometry(), false );
        while( iter.hasMore() )
        {
            Geometry* part = iter.next();

            osg::ref_ptr<osg::Geometry> walls = new osg::Geometry();
            //walls->setUseVertexBufferObjects(true);
            
            osg::ref_ptr<osg::Geometry> rooflines = 0L;
            osg::ref_ptr<osg::Geometry> outlines  = 0L;
            
            if ( part->getType() == Geometry::TYPE_POLYGON )
            {
                rooflines = new osg::Geometry();
                //rooflines->setUseVertexBufferObjects(true);

                // prep the shapes by making sure all polys are open:
                static_cast<Polygon*>(part)->open();
            }

            // fire up the outline geometry if we have a line symbol.
            if ( _outlineSymbol != 0L )
            {
                outlines = new osg::Geometry();
            }

            // calculate the extrusion height:
            float height;

            if ( _heightCallback.valid() )
            {
                height = _heightCallback->operator()(input, context);
            }
            else if ( _heightExpr.isSet() )
            {
                height = input->eval( _heightExpr.mutable_value() );
            }
            else
            {
                height = *_extrusionSymbol->height();
            }

            // calculate the height offset from the base:
            float offset = 0.0;
            if ( _heightOffsetExpr.isSet() )
            {
                offset = input->eval( _heightOffsetExpr.mutable_value() );
            }

            osg::StateSet* wallStateSet = 0L;
            osg::StateSet* roofStateSet = 0L;

            // calculate the wall texturing:
            SkinResource* wallSkin = 0L;
            if ( _wallSkinSymbol.valid() )
            {
                if ( _wallResLib.valid() )
                {
                    SkinSymbol querySymbol( *_wallSkinSymbol.get() );
                    querySymbol.objectHeight() = fabs(height) - offset;
                    wallSkin = _wallResLib->getSkin( &querySymbol, wallSkinPRNG );
                }

                else
                {
                    //TODO: simple single texture?
                }
            }

            // calculate the rooftop texture:
            SkinResource* roofSkin = 0L;
            if ( _roofSkinSymbol.valid() )
            {
                if ( _roofResLib.valid() )
                {
                    SkinSymbol querySymbol( *_roofSkinSymbol.get() );
                    roofSkin = _roofResLib->getSkin( &querySymbol, roofSkinPRNG );
                }

                else
                {
                    //TODO: simple single texture?
                }
            }

            // calculate the colors:
            osg::Vec4f wallColor(1,1,1,1), roofColor(1,1,1,1), outlineColor(1,1,1,1);

            if ( _wallPolygonSymbol.valid() )
            {
                wallColor = _wallPolygonSymbol->fill()->color();
            }
            if ( _roofPolygonSymbol.valid() )
            {
                roofColor = _roofPolygonSymbol->fill()->color();
            }
            if ( _outlineSymbol.valid() )
            {
                outlineColor = _outlineSymbol->stroke()->color();
            }

            // Create the extruded geometry!
            if (extrudeGeometry( 
                    part, height, offset, 
                    *_extrusionSymbol->flatten(),
                    walls.get(), rooflines.get(), 0L, outlines.get(),
                    wallColor, roofColor, outlineColor,
                    wallSkin, roofSkin,
                    context ) )
            {      
                if ( wallSkin )
                {
                    wallStateSet = context.resourceCache()->getStateSet( wallSkin );
                }

                // generate per-vertex normals, altering the geometry as necessary to avoid
                // smoothing around sharp corners
    #if OSG_MIN_VERSION_REQUIRED(2,9,9)
                //Crease angle threshold wasn't added until
                osgUtil::SmoothingVisitor::smooth(
                    *walls.get(), 
                    osg::DegreesToRadians(_wallAngleThresh_deg) );            
    #else
                osgUtil::SmoothingVisitor::smooth(*walls.get());            
    #endif

                // tessellate and add the roofs if necessary:
                if ( rooflines.valid() )
                {
                    osgUtil::Tessellator tess;
                    tess.setTessellationType( osgUtil::Tessellator::TESS_TYPE_GEOMETRY );
                    tess.setWindingType( osgUtil::Tessellator::TESS_WINDING_ODD ); //POSITIVE );
                    tess.retessellatePolygons( *(rooflines.get()) );

                    // generate default normals (no crease angle necessary; they are all pointing up)
                    // TODO do this manually; probably faster
                    osgUtil::SmoothingVisitor::smooth( *rooflines.get() );

                    // texture the rooflines if necessary
                    //applyOverlayTexturing( rooflines.get(), input, env );

                    // mark this geometry as DYNAMIC because otherwise the OSG optimizer will destroy it.
                    // TODO: why??
                    rooflines->setDataVariance( osg::Object::DYNAMIC );

                    if ( roofSkin )
                    {
                        roofStateSet = context.resourceCache()->getStateSet( roofSkin );
                    }
                }

                std::string name;
                if ( !_featureNameExpr.empty() )
                    name = input->eval( _featureNameExpr );

                //MeshConsolidator::run( *walls.get() );
                addDrawable( walls.get(), wallStateSet, name );

                if ( rooflines.valid() )
                {
                    //MeshConsolidator::run( *rooflines.get() );
                    addDrawable( rooflines.get(), roofStateSet, name );
                }

                if ( outlines.valid() )
                {
                    addDrawable( outlines.get(), 0L, name );
                }
            }   
        }
    }

    return true;
}

Here is the call graph for this function:

Here is the caller graph for this function:

osg::Node * ExtrudeGeometryFilter::push ( FeatureList input,
FilterContext context 
) [virtual]

Pushes a list of features through the filter.

Implements osgEarth::Features::FeaturesToNodeFilter.

Definition at line 800 of file ExtrudeGeometryFilter.cpp.

{
    reset( context );

    // minimally, we require an extrusion symbol.
    if ( !_extrusionSymbol.valid() )
    {
        OE_WARN << LC << "Missing required extrusion symbolology; geometry will be empty" << std::endl;
        return new osg::Group();
    }

    // establish the active resource library, if applicable.
    _wallResLib = 0L;
    _roofResLib = 0L;

    const StyleSheet* sheet = context.getSession()->styles();

    if ( sheet != 0L )
    {
        if ( _wallSkinSymbol.valid() && _wallSkinSymbol->libraryName().isSet() )
        {
            _wallResLib = sheet->getResourceLibrary( *_wallSkinSymbol->libraryName() );
            if ( !_wallResLib.valid() )
            {
                OE_WARN << LC << "Unable to load resource library '" << *_wallSkinSymbol->libraryName() << "'"
                    << "; wall geometry will not be textured." << std::endl;
            }
        }

        if ( _roofSkinSymbol.valid() && _roofSkinSymbol->libraryName().isSet() )
        {
            _roofResLib = sheet->getResourceLibrary( *_roofSkinSymbol->libraryName() );
            if ( !_roofResLib.valid() )
            {
                OE_WARN << LC << "Unable to load resource library '" << *_roofSkinSymbol->libraryName() << "'"
                    << "; roof geometry will not be textured." << std::endl;
            }
        }
    }

    // calculate the localization matrices (_local2world and _world2local)
    computeLocalizers( context );

    // push all the features through the extruder.
    bool ok = process( input, context );

    // convert everything to triangles and combine drawables.
    if ( _mergeGeometry == true && _featureNameExpr.empty() )
    {
        for( SortedGeodeMap::iterator i = _geodes.begin(); i != _geodes.end(); ++i )
        {
            MeshConsolidator::run( *i->second.get() );
        }
    }

    // parent geometry with a delocalizer (if necessary)
    osg::Group* group = createDelocalizeGroup();
    
    // combines geometries where the statesets are the same.
    for( SortedGeodeMap::iterator i = _geodes.begin(); i != _geodes.end(); ++i )
    {
        group->addChild( i->second.get() );
    }
    _geodes.clear();

    // if we drew outlines, apply a poly offset too.
    if ( _outlineSymbol.valid() )
    {
        osg::StateSet* groupStateSet = group->getOrCreateStateSet();
        groupStateSet->setAttributeAndModes( new osg::PolygonOffset(1,1), 1 );
        if ( _outlineSymbol->stroke()->width().isSet() )
            groupStateSet->setAttributeAndModes( new osg::LineWidth(*_outlineSymbol->stroke()->width()), 1 );
    }

    OE_DEBUG << LC << "Sorted geometry into " << group->getNumChildren() << " groups" << std::endl;

    //TODO
    // running this after the MC reduces the primitive set count by a huge amount, but I
    // have not figured out why yet.
    if ( _mergeGeometry == true )
    {
        osgUtil::Optimizer o;
        o.optimize( group, osgUtil::Optimizer::MERGE_GEOMETRY );
    }

    return group;
}

Here is the call graph for this function:

Here is the caller graph for this function:

void ExtrudeGeometryFilter::reset ( const FilterContext context) [protected]

Definition at line 89 of file ExtrudeGeometryFilter.cpp.

{
    _cosWallAngleThresh = cos( _wallAngleThresh_deg );
    _geodes.clear();

    if ( _styleDirty )
    {
        const StyleSheet* sheet = context.getSession()->styles();

        _wallSkinSymbol    = 0L;
        _wallPolygonSymbol = 0L;
        _roofSkinSymbol    = 0L;
        _roofPolygonSymbol = 0L;
        _extrusionSymbol   = 0L;
        _outlineSymbol     = 0L;

        _extrusionSymbol = _style.get<ExtrusionSymbol>();
        if ( _extrusionSymbol.valid() )
        {
            // make a copy of the height expression so we can use it:
            if ( _extrusionSymbol->heightExpression().isSet() )
            {
                _heightExpr = *_extrusionSymbol->heightExpression();
            }

            // account for a "height" value that is relative to ZERO (MSL/HAE)
            AltitudeSymbol* alt = _style.get<AltitudeSymbol>();
            if ( alt && !_extrusionSymbol->heightExpression().isSet() )
            {
                if (alt->clamping() == AltitudeSymbol::CLAMP_ABSOLUTE ||
                    alt->clamping() == AltitudeSymbol::CLAMP_RELATIVE_TO_TERRAIN )
                {
                    _heightExpr = NumericExpression( "0-[__max_hat]" );
                }
            }
            
            // attempt to extract the wall symbols:
            if ( _extrusionSymbol->wallStyleName().isSet() && sheet != 0L )
            {
                const Style* wallStyle = sheet->getStyle( *_extrusionSymbol->wallStyleName(), false );
                if ( wallStyle )
                {
                    _wallSkinSymbol = wallStyle->get<SkinSymbol>();
                    _wallPolygonSymbol = wallStyle->get<PolygonSymbol>();
                }
            }

            // attempt to extract the rooftop symbols:
            if ( _extrusionSymbol->roofStyleName().isSet() && sheet != 0L )
            {
                const Style* roofStyle = sheet->getStyle( *_extrusionSymbol->roofStyleName(), false );
                if ( roofStyle )
                {
                    _roofSkinSymbol = roofStyle->get<SkinSymbol>();
                    _roofPolygonSymbol = roofStyle->get<PolygonSymbol>();
                }
            }

            // if there's a line symbol, use it to outline the extruded data.
            _outlineSymbol = _style.get<LineSymbol>();
        }

        // backup plan for skin symbols:
        const SkinSymbol* skin = _style.get<SkinSymbol>();
        if ( skin )
        {
            if ( !_wallSkinSymbol.valid() )
                _wallSkinSymbol = skin;
            if ( !_roofSkinSymbol.valid() )
                _roofSkinSymbol = skin;
        }

        // backup plan for poly symbols:
        const PolygonSymbol* poly = _style.get<PolygonSymbol>();
        if ( poly )
        {
            if ( !_wallPolygonSymbol.valid() )
                _wallPolygonSymbol = poly;
            if ( !_roofPolygonSymbol.valid() )
                _roofPolygonSymbol = poly;
        }

        _styleDirty = false;
    }
}

Here is the call graph for this function:

Here is the caller graph for this function:

void osgEarth::Features::ExtrudeGeometryFilter::setFeatureNameExpr ( const StringExpression expr) [inline]

Sets the expression to evaluate when setting a feature name. NOTE: setting this forces geometry-merging to OFF

Definition at line 72 of file ExtrudeGeometryFilter.

{ _featureNameExpr = expr; }

Here is the caller graph for this function:

void ExtrudeGeometryFilter::setStyle ( const Style style)

Sets the style that will govern the geometry generation.

Definition at line 82 of file ExtrudeGeometryFilter.cpp.

{
    _style      = style;
    _styleDirty = true;
}

Here is the caller graph for this function:

void osgEarth::Features::ExtrudeGeometryFilter::setWallAngleThreshold ( float  angle_deg) [inline]

Sets the maximum wall angle that doesn't require a new normal vector

Definition at line 66 of file ExtrudeGeometryFilter.

{ _wallAngleThresh_deg = angle_deg; }

Member Data Documentation

Definition at line 86 of file ExtrudeGeometryFilter.

Definition at line 95 of file ExtrudeGeometryFilter.

Definition at line 87 of file ExtrudeGeometryFilter.

Definition at line 80 of file ExtrudeGeometryFilter.

Definition at line 88 of file ExtrudeGeometryFilter.

Definition at line 90 of file ExtrudeGeometryFilter.

Definition at line 89 of file ExtrudeGeometryFilter.

Definition at line 83 of file ExtrudeGeometryFilter.

Definition at line 84 of file ExtrudeGeometryFilter.

osg::ref_ptr<osg::StateSet> osgEarth::Features::ExtrudeGeometryFilter::_noTextureStateSet [protected]

Definition at line 81 of file ExtrudeGeometryFilter.

Definition at line 100 of file ExtrudeGeometryFilter.

Definition at line 99 of file ExtrudeGeometryFilter.

Definition at line 102 of file ExtrudeGeometryFilter.

Definition at line 98 of file ExtrudeGeometryFilter.

Definition at line 92 of file ExtrudeGeometryFilter.

Definition at line 93 of file ExtrudeGeometryFilter.

Definition at line 85 of file ExtrudeGeometryFilter.

Definition at line 97 of file ExtrudeGeometryFilter.

Definition at line 101 of file ExtrudeGeometryFilter.

Definition at line 96 of file ExtrudeGeometryFilter.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines