def filter_declarations(self): code_generator_t.filter_declarations(self) # rename STL vectors/maps of certain types self.std_ns.class_('vector< ompl::tools::Benchmark::PlannerExperiment >').rename( 'vectorPlannerExperiment') self.std_ns.class_('vector< std::vector< std::map<std::string, std::string> > >').rename( 'vectorRunProgressData') # make objects printable that have a print function self.replace_member_functions(self.ompl_ns.member_functions('print')) benchmark_cls = self.ompl_ns.class_('Benchmark') self.replace_member_function(benchmark_cls.member_function('benchmark')) for constructor in benchmark_cls.constructors(arg_types=[None, "::std::string const &"]): constructor.add_transformation(FT.input(1)) # don't want to export iostream benchmark_cls.member_function('saveResultsToStream').exclude() self.ompl_ns.member_functions('addPlannerAllocator').exclude() self.replace_member_functions(benchmark_cls.member_functions( lambda method: method.name.startswith('set') and method.name.endswith('Event'))) benchmark_cls.add_registration_code( 'def("addPlannerAllocator", &ompl::tools::Benchmark::addPlannerAllocator)') self.ompl_ns.class_('OptimizePlan').add_registration_code( 'def("addPlannerAllocator", &ompl::tools::OptimizePlan::addPlannerAllocator)') self.add_function_wrapper('void(const ompl::base::PlannerPtr)', \ 'PreSetupEvent', 'Pre-setup event') self.add_function_wrapper( 'void(ompl::base::PlannerPtr, ompl::tools::Benchmark::RunProperties&)', 'PostSetupEvent', 'Post-setup event') benchmark_cls.class_('Request').no_init = False
def filter_declarations(self): # force ProblemDefinition to be included, because it is used by other modules self.ompl_ns.class_('ProblemDefinition').include() # force the abstract base class Path to be included, because it is used by other modules self.ompl_ns.class_('Path').include() code_generator_t.filter_declarations(self) # rename STL vectors of certain types self.std_ns.class_( 'map< std::string, std::shared_ptr< ompl::base::ProjectionEvaluator > >').rename( 'mapStringToProjectionEvaluator') self.std_ns.class_('vector< ompl::base::State * >').rename('vectorState') try: self.std_ns.class_('vector< ompl::base::State const* >').rename('vectorConstState') except declaration_not_found_t: pass self.std_ns.class_('vector< std::shared_ptr<ompl::base::StateSpace> >').rename( 'vectorStateSpacePtr') #self.std_ns.class_('vector< <ompl::base::PlannerSolution> >').rename( # 'vectorPlannerSolution') self.std_ns.class_('map< std::string, std::shared_ptr<ompl::base::GenericParam> >').rename( 'mapStringToGenericParam') self.std_ns.class_('map< std::string, ompl::base::StateSpace::SubstateLocation >').rename( 'mapStringToSubstateLocation') self.std_ns.class_('vector<ompl::base::PlannerSolution>').rename('vectorPlannerSolution') pairStateDouble = self.std_ns.class_('pair<ompl::base::State *, double>') pairStateDouble.rename('pairStateDouble') pairStateDouble.include() # this operator seems to cause problems with g++-6 pairStateDouble.operators('=').exclude() # rename some templated types self.ompl_ns.class_('SpecificParam< bool >').rename('SpecificParamBool') self.ompl_ns.class_('SpecificParam< char >').rename('SpecificParamChar') self.ompl_ns.class_('SpecificParam< int >').rename('SpecificParamInt') self.ompl_ns.class_('SpecificParam< unsigned int >').rename('SpecificParamUint') self.ompl_ns.class_('SpecificParam< float >').rename('SpecificParamFloat') self.ompl_ns.class_('SpecificParam< double >').rename('SpecificParamDouble') self.ompl_ns.class_('SpecificParam< long double >').rename('SpecificParamLongDouble') self.ompl_ns.class_('SpecificParam< std::basic_string<char> >').rename( 'SpecificParamString') for cls in self.ompl_ns.classes(lambda decl: decl.name.startswith('SpecificParam')): cls.constructors().exclude() # don't export variables that need a wrapper self.ompl_ns.variables(lambda decl: decl.is_wrapper_needed()).exclude() # force StateSpace::allocState to be exported. # (not sure why this is necessary) allocStateFn = self.ompl_ns.class_('StateSpace').member_function('allocState') allocStateFn.include() allocStateFn.call_policies = \ call_policies.return_value_policy(call_policies.reference_existing_object) # rename the abstract base class State to AbstractState state = self.ompl_ns.class_('State') state.rename('AbstractState') # don't export components which is of type State** state = self.ompl_ns.class_('CompoundState') state.variable('components').exclude() state.rename('CompoundStateInternal') # rename a ScopedState<> to State bstate = self.ompl_ns.class_('ScopedState< ompl::base::StateSpace >') bstate.rename('State') bstate.operator('=', arg_types=['::ompl::base::State const &']).exclude() # add array access to double components of state self.add_array_access(bstate, 'double') # loop over all predefined state spaces spaces = [s.related_class.name.replace('StateSpace', '') \ for s in self.ompl_ns.class_('StateSpace').recursive_derived] for stype in spaces: # create a python type for each of their corresponding state types state = self.ompl_ns.class_('ScopedState< ompl::base::%sStateSpace >' % stype) state.rename(stype+'State') state.operator('=', arg_types=['::ompl::base::State const &']).exclude() # add a constructor that allows, e.g., an SE3State to be constructed from a State state.add_registration_code( 'def(bp::init<ompl::base::ScopedState<ompl::base::StateSpace> const &>' \ '(( bp::arg("other") )))') # mark the space statetype as 'internal' to emphasize that it # shouldn't typically be used by a regular python user try: self.ompl_ns.class_(stype + 'StateSpace').decls('StateType').rename( stype + 'StateInternal') except: # ignore derived statespaces that do not define their own StateType pass # add a constructor that allows, e.g., a State to be constructed from a SE3State bstate.add_registration_code( 'def(bp::init<ompl::base::ScopedState<ompl::base::%sStateSpace> const &>' \ '(( bp::arg("other") )))' % stype) # add array access to double components of state self.add_array_access(state, 'double') # I don't know how to export a C-style array of an enum type for stype in ['Dubins', 'ReedsShepp']: self.ompl_ns.enumeration(stype + 'PathSegmentType').exclude() self.ompl_ns.class_(stype + 'Path').exclude() self.ompl_ns.class_(stype + 'StateSpace').member_function( stype[0].lower()+stype[1:]).exclude() # don't expose these utility functions that return double* self.ompl_ns.member_functions('getValueAddressAtIndex').exclude() self.ompl_ns.member_functions('getValueAddressAtName').exclude() self.ompl_ns.member_functions('getValueAddressAtLocation').exclude() # don't export vector<ValueLocation> self.ompl_ns.member_functions('getValueLocations').exclude() # don't export map<std::string, ValueLocation> self.ompl_ns.member_functions('getValueLocationsByName').exclude() # exclude member function for which there are multiple signatures self.ompl_ns.class_('Goal').member_function( 'isSatisfied', arg_types=['::ompl::base::State const *', 'double *']).exclude() # don't expose double* self.ompl_ns.class_('RealVectorStateSpace').class_( 'StateType').variable('values').exclude() try: stateStorage = self.ompl_ns.class_('StateStorage') stateStorage.member_function('getStateSamplerAllocatorRange').exclude() stateStorage.add_registration_code('def("getStateSamplerAllocatorRange", ' \ '&ompl::base::StateStorage::getStateSamplerAllocatorRange)') except declaration_not_found_t: pass cls = self.ompl_ns.class_('PlannerStatus') # rename to something more memorable than the default Py++ name for # the casting operator: # as__scope_ompl_scope_base_scope_PlannerStatus_scope_StatusType cls.operator( lambda decl: decl.name == 'operator ::ompl::base::PlannerStatus::StatusType').rename( 'getStatus') # for python 2.x cls.add_registration_code( 'def("__nonzero__", &ompl::base::PlannerStatus::operator bool)') # for python 3.x cls.add_registration_code( 'def("__bool__", &ompl::base::PlannerStatus::operator bool)') # Using nullptr as a default value in method arguments causes # problems with Boost.Python. # See https://github.com/boostorg/python/issues/60 self.ompl_ns.class_('ProblemDefinition').add_declaration_code('#define nullptr NULL\n') try: for cls in ['AtlasChart', 'AtlasStateSpace', 'ConstrainedStateSpace', \ 'ProjectedStateSpace', 'TangentBundleStateSpace']: self.ompl_ns.class_(cls).add_declaration_code('#define nullptr NULL\n') self.ompl_ns.class_('AtlasChart').member_function('toPolygon').exclude() self.replace_member_function(self.ompl_ns.class_( 'AtlasStateSpace').member_function('printPLY')) self.add_function_wrapper( 'double(ompl::base::AtlasChart *)', 'AtlasChartBiasFunction', 'Bias function for sampling a chart from an atlas.') # add code for numpy.array <-> Eigen conversions self.mb.add_declaration_code(open(join(dirname(__file__), \ 'numpy_eigen.cpp'), 'r').read()) self.mb.add_registration_code(""" EIGEN_ARRAY_CONVERTER(Eigen::MatrixXd, 2) EIGEN_ARRAY_CONVERTER(Eigen::VectorXd, 1) """) self.mb.add_registration_code('np::initialize();', tail=False) self.add_array_access(self.ompl_ns.class_( 'ConstrainedStateSpace').class_('StateType'), 'double') for cls in [self.ompl_ns.class_('Constraint'), self.ompl_ns.class_('ConstraintIntersection')]: for method in ['function', 'jacobian']: cls.member_function(method, arg_types=[ '::Eigen::Ref<const Eigen::Matrix<double, -1, 1, 0, -1, 1>, ' '0, Eigen::InnerStride<1> > const &', None]).add_transformation(FT.input(0)) cls = self.ompl_ns.class_('Constraint') for method in ['distance', 'isSatisfied']: cls.member_function(method, arg_types=[ '::Eigen::Ref<const Eigen::Matrix<double, -1, 1, 0, -1, 1>, ' '0, Eigen::InnerStride<1> > const &']).add_transformation(FT.input(0)) except: # python bindings for constrained planning code is only generated # if boost.numpy was found pass # Exclude PlannerData::getEdges function that returns a map of PlannerDataEdge* for now #self.ompl_ns.class_('PlannerData').member_functions('getEdges').exclude() #self.std_ns.class_('map< unsigned int, ompl::base::PlannerDataEdge const*>').include() mapUintToPlannerDataEdge_cls = self.std_ns.class_( 'map< unsigned int, const ompl::base::PlannerDataEdge *>') mapUintToPlannerDataEdge_cls.rename('mapUintToPlannerDataEdge') mapUintToPlannerDataEdge_cls.indexing_suite.call_policies = \ call_policies.return_value_policy(call_policies.reference_existing_object) # Remove Boost.Graph representation from PlannerData plannerData = self.ompl_ns.class_('PlannerData') plannerData.member_functions('toBoostGraph').exclude() # Make PlannerData printable self.replace_member_function(plannerData.member_function('printGraphviz')) self.replace_member_function(plannerData.member_function('printGraphML')) # serialize passes archive by reference which causes problems self.ompl_ns.class_('PlannerDataVertex').member_functions('serialize').exclude() self.ompl_ns.class_('PlannerDataEdge').member_functions('serialize').exclude() # add array indexing to the RealVectorState self.add_array_access(self.ompl_ns.class_('RealVectorStateSpace').class_('StateType')) # make objects printable that have a print function self.replace_member_functions(self.ompl_ns.member_functions('print')) # handle special case (abstract base class with pure virtual method) self.ompl_ns.class_('Path').add_wrapper_code( 'virtual void print(std::ostream&) const {}') # make settings printable self.replace_member_functions(self.ompl_ns.member_functions('printSettings')) # make properties printable self.replace_member_functions(self.ompl_ns.member_functions('printProperties')) # make states printable self.replace_member_functions(self.ompl_ns.member_functions('printState')) # make list of available projections printable self.replace_member_functions(self.ompl_ns.member_functions('printProjections')) # make projections printable self.replace_member_functions(self.ompl_ns.member_functions('printProjection')) # make state space diagram printable self.replace_member_function(self.ompl_ns.class_('StateSpace').member_function('Diagram')) # make state space list printable self.replace_member_function(self.ompl_ns.class_('StateSpace').member_function('List')) # add wrappers for std::function types self.add_function_wrapper('bool(const ompl::base::GoalLazySamples*, ompl::base::State*)', \ 'GoalSamplingFn', 'Goal sampling function') self.add_function_wrapper('void(const ompl::base::State*)', \ 'NewStateCallbackFn', 'New state callback function') self.add_function_wrapper( 'ompl::base::PlannerPtr(const ompl::base::SpaceInformationPtr&)', 'PlannerAllocator', 'Planner allocator') self.add_function_wrapper('bool()', \ 'PlannerTerminationConditionFn', 'Planner termination condition function') self.add_function_wrapper('bool(const ompl::base::State*)', \ 'StateValidityCheckerFn', 'State validity checker function') self.add_function_wrapper('ompl::base::StateSamplerPtr(const ompl::base::StateSpace*)', \ 'StateSamplerAllocator', 'State sampler allocator') self.add_function_wrapper( 'ompl::base::ValidStateSamplerPtr(ompl::base::SpaceInformation const*)', 'ValidStateSamplerAllocator', 'Valid state allocator function') self.add_function_wrapper('double(const ompl::base::PlannerDataVertex&, ' \ 'const ompl::base::PlannerDataVertex&, const ompl::base::PlannerDataEdge&)', \ 'EdgeWeightFn', 'Edge weight function') self.add_function_wrapper( 'ompl::base::Cost(const ompl::base::State*, const ompl::base::Goal*)', 'CostToGoHeuristic', 'Cost-to-go heuristic for optimizing planners') self.add_function_wrapper('std::string()', 'PlannerProgressProperty', \ 'Function that returns stringified value of a property while a planner is running') # rename SamplerSelectors self.ompl_ns.class_('SamplerSelector< ompl::base::StateSampler >').rename( 'StateSamplerSelector') self.ompl_ns.class_('SamplerSelector< ompl::base::ValidStateSampler >').rename( 'ValidStateSamplerSelector') try: cls = self.ompl_ns.class_('StateStorage').member_functions('load') self.ompl_ns.class_('StateStorage').member_function('load', \ arg_types=['::std::istream &']).exclude() self.ompl_ns.class_('StateStorage').member_function('store', \ arg_types=['::std::ostream &']).exclude() except declaration_not_found_t: pass
def customize( self, mb ): mb.global_ns.calldefs().create_with_signature = True hello_world = mb.free_fun( 'hello_world' ) hello_world.add_transformation( ft.output(0) ) calc = mb.class_('calculator_t' ) assign_funs = calc.mem_funs( lambda decl: decl.name.startswith( 'assign' ) ) assign_funs.add_transformation( ft.output(0), ft.output(1) ) clone_and_assign_5 = calc.mem_fun( 'clone_and_assign_5' ) clone_and_assign_5.add_transformation( ft.output(0) ) clone_and_assign_5.call_policies = call_policies.return_value_policy( call_policies.manage_new_object ) window = mb.class_( 'window_t' ) window.mem_fun( 'resize' ).add_transformation( ft.input(0), ft.input(1) ) window.mem_fun( 'resize_in_out' ).add_transformation( ft.inout(0), ft.inout(1) ) point3d = mb.class_( 'point3d_t' ) point3d.add_wrapper_code( '' ) point3d.mem_fun( 'initialize' ).add_transformation( ft.input_static_array(0, size=3) ) point3d.mem_fun( 'position' ).add_transformation( ft.output_static_array(0, size=3) ) point3d.mem_fun( 'distance' ).add_transformation( ft.output(1) ) image = mb.class_( "image_t" ) image.always_expose_using_scope = True image.member_function( "get_size" ) image.member_function( "get_size" ).add_transformation( ft.output(0), ft.output(1) ) image.member_function( "get_one_value" ).add_transformation( ft.output(0) ) image.member_function( "get_size2" ).add_transformation( ft.output(0), ft.output(1) ) image.member_function( "input_arg" ).add_transformation( ft.input(0) ) image.member_function( "fixed_input_array" ).add_transformation( ft.input_static_array(0,3) ) image.member_function( "fixed_output_array" ).add_transformation( ft.output_static_array(0,3) ) mb.free_function("get_cpp_instance").call_policies \ = call_policies.return_value_policy(call_policies.reference_existing_object) mb.variable( "cpp_instance" ).exclude() cls = mb.class_("no_virtual_members_t") cls.member_function("member").add_transformation( ft.output(0) ) cls = mb.class_("ft_private_destructor_t") cls.member_function("get_value").add_transformation( ft.output(0) ) mb.decls(lambda decl: decl.name.startswith("_")).exclude() cls = mb.class_("bug_render_target_t") cls.mem_fun("get_statistics", arg_types=['float &']*2).add_transformation( ft.output(0), ft.output(1) ) cls = mb.class_( 'modify_type_tester_t' ) do_nothing = cls.mem_fun( 'do_nothing' ) do_nothing.add_transformation( ft.modify_type(0, declarations.remove_reference ) ) clone = cls.mem_fun( 'clone' ) clone.call_policies = call_policies.return_value_policy( call_policies.manage_new_object ) clone.add_transformation( ft.modify_type(0, declarations.remove_reference ) ) cls = mb.class_( 'input_c_buffer_tester_t') write_mf = cls.mem_fun( 'write' ) write_mf.add_transformation( ft.input_c_buffer( 'buffer', 'size' ) ) write_s = cls.mem_fun( 'write_s' ) write_s.add_transformation( ft.input_c_buffer( 'buffer', 'size' ) ) resource = mb.class_( 'resources_t' ) resource.held_type = 'std::auto_ptr< %s >' % resource.decl_string transfer_ownership_tester = mb.class_( 'transfer_ownership_tester_t' ) tester = transfer_ownership_tester.mem_fun( 'tester' ) tester.add_transformation( ft.transfer_ownership( 0 ) ) render_queue_listener_t = mb.class_( 'render_queue_listener_t' ) render_queue_ended = render_queue_listener_t.mem_fun( 'render_queue_ended' ) render_queue_ended.add_transformation( ft.inout(2) )
def customize( self, mb ): mb.global_ns.calldefs().create_with_signature = True hello_world = mb.free_fun( 'hello_world' ) hello_world.add_transformation( ft.output(0) ) calc = mb.class_('calculator_t' ) assign_funs = calc.mem_funs( lambda decl: decl.name.startswith( 'assign' ) ) assign_funs.add_transformation( ft.output(0), ft.output(1) ) clone_and_assign_5 = calc.mem_fun( 'clone_and_assign_5' ) clone_and_assign_5.add_transformation( ft.output(0) ) clone_and_assign_5.call_policies = call_policies.return_value_policy( call_policies.manage_new_object ) window = mb.class_( 'window_t' ) window.mem_fun( 'resize' ).add_transformation( ft.input(0), ft.input(1) ) window.mem_fun( 'resize_in_out' ).add_transformation( ft.inout(0), ft.inout(1) ) point3d = mb.class_( 'point3d_t' ) point3d.add_wrapper_code( '' ) point3d.mem_fun( 'initialize' ).add_transformation( ft.input_static_array(0, size=3) ) point3d.mem_fun( 'position' ).add_transformation( ft.output_static_array(0, size=3) ) distance = point3d.mem_fun( 'distance' ) distance.add_transformation( ft.output(1) ) distance.transformations[0].controller.add_pre_call_code( '//dddddddddddddd' ) distance.transformations[0].controller.add_post_call_code( '//qqqqqqqqqqqqq' ) image = mb.class_( "image_t" ) image.always_expose_using_scope = True image.member_function( "get_size" ) image.member_function( "get_size" ).add_transformation( ft.output(0), ft.output(1) ) image.member_function( "get_one_value" ).add_transformation( ft.output(0) ) image.member_function( "get_size2" ).add_transformation( ft.output(0), ft.output(1) ) image.member_function( "input_arg" ).add_transformation( ft.input(0) ) image.member_function( "fixed_input_array" ).add_transformation( ft.input_static_array(0,3) ) image.member_function( "fixed_output_array" ).add_transformation( ft.output_static_array(0,3) ) mb.free_function("get_cpp_instance").call_policies \ = call_policies.return_value_policy(call_policies.reference_existing_object) mb.variable( "cpp_instance" ).exclude() cls = mb.class_("no_virtual_members_t") cls.member_function("member").add_transformation( ft.output(0) ) cls = mb.class_("ft_private_destructor_t") cls.member_function("get_value").add_transformation( ft.output(0) ) mb.decls(lambda decl: decl.name.startswith("_")).exclude() cls = mb.class_("bug_render_target_t") cls.mem_fun("get_statistics", arg_types=['float &']*2).add_transformation( ft.output(0), ft.output(1) ) cls = mb.class_( 'modify_type_tester_t' ) do_nothing = cls.mem_fun( 'do_nothing' ) do_nothing.add_transformation( ft.modify_type(0, declarations.remove_reference ) ) clone = cls.mem_fun( 'clone' ) clone.call_policies = call_policies.return_value_policy( call_policies.manage_new_object ) clone.add_transformation( ft.modify_type(0, declarations.remove_reference ) ) cls = mb.class_( 'input_c_buffer_tester_t') write_mf = cls.mem_fun( 'write' ) write_mf.add_transformation( ft.input_c_buffer( 'buffer', 'size' ) ) write_s = cls.mem_fun( 'write_s' ) write_s.add_transformation( ft.input_c_buffer( 'buffer', 'size' ) ) resource = mb.class_( 'resources_t' ) resource.held_type = 'std::auto_ptr< %s >' % resource.decl_string transfer_ownership_tester = mb.class_( 'transfer_ownership_tester_t' ) tester = transfer_ownership_tester.mem_fun( 'tester' ) tester.add_transformation( ft.transfer_ownership( 0 ) ) render_queue_listener_t = mb.class_( 'render_queue_listener_t' ) render_queue_ended = render_queue_listener_t.mem_fun( 'render_queue_ended' ) render_queue_ended.add_transformation( ft.inout(2) ) ft_bugs = mb.namespace( 'ft_bugs' ) h = ft_bugs.mem_fun( 'h' ) h.add_transformation( ft.modify_type(0, remove_const_ref ) ) h.call_policies = call_policies.return_internal_reference() h2 = ft_bugs.mem_fun( 'h2' ) h2.add_transformation( ft.modify_type(0, remove_const_ref ) ) h2.call_policies = call_policies.return_internal_reference() ft_bugs.class_( 'B' ).always_expose_using_scope = True ft_bugs.mem_fun( 'get_a' ).call_policies \ = call_policies.return_value_policy( call_policies.reference_existing_object ) ft_bugs2 = mb.namespace( 'ft_bugs2' ) g = ft_bugs2.mem_fun( 'g' ) g.add_transformation( ft.modify_type(0, remove_const_ref ) ) g.call_policies = call_policies.return_internal_reference()
# getVariableInt.call_policies = call_policies.return_value_policy(call_policies.manage_new_object) # generalfilereader.include() attribute = mb.class_("Attribute") attribute.include() # setAttrFuncs = attribute.member_functions('setAttributeValue') # for setAttr in setAttrFuncs: # setAttr.add_transformation(FT.input(0)) setAttrStr = attribute.mem_fun('setAttributeValue', arg_types = ['::std::string &']) setAttrFloat = attribute.mem_fun('setAttributeValue', arg_types = ['float &']) setAttrInt = attribute.mem_fun('setAttributeValue', arg_types = ['int &']) setAttrStr.add_transformation( FT.input(0), alias = 'setAttrStr' ) setAttrFloat.add_transformation( FT.input(0), alias = 'setAttrFloat' ) setAttrInt.add_transformation( FT.input(0), alias = 'setAttrInt' ) attribute.add_property( 'attributeName' , attribute.member_function('getAttributeName') , attribute.member_function('setAttributeName')) attribute.add_property( 'sValue' , attribute.member_function('getAttributeString') , setAttrStr) attribute.add_property( 'iValue' , attribute.member_function('getAttributeInt') , setAttrInt) attribute.add_property( 'fValue' , attribute.member_function('getAttributeFloat')
def customize(self, mb): mb.global_ns.calldefs().create_with_signature = True hello_world = mb.free_fun("hello_world") hello_world.add_transformation(ft.output(0)) calc = mb.class_("calculator_t") assign_funs = calc.mem_funs(lambda decl: decl.name.startswith("assign")) assign_funs.add_transformation(ft.output(0), ft.output(1)) clone_and_assign_5 = calc.mem_fun("clone_and_assign_5") clone_and_assign_5.add_transformation(ft.output(0)) clone_and_assign_5.call_policies = call_policies.return_value_policy(call_policies.manage_new_object) window = mb.class_("window_t") window.mem_fun("resize").add_transformation(ft.input(0), ft.input(1)) window.mem_fun("resize_in_out").add_transformation(ft.inout(0), ft.inout(1)) point3d = mb.class_("point3d_t") point3d.add_wrapper_code("") point3d.mem_fun("initialize").add_transformation(ft.input_static_array(0, size=3)) point3d.mem_fun("position").add_transformation(ft.output_static_array(0, size=3)) point3d.mem_fun("distance").add_transformation(ft.output(1)) image = mb.class_("image_t") image.always_expose_using_scope = True image.member_function("get_size") image.member_function("get_size").add_transformation(ft.output(0), ft.output(1)) image.member_function("get_one_value").add_transformation(ft.output(0)) image.member_function("get_size2").add_transformation(ft.output(0), ft.output(1)) image.member_function("input_arg").add_transformation(ft.input(0)) image.member_function("fixed_input_array").add_transformation(ft.input_static_array(0, 3)) image.member_function("fixed_output_array").add_transformation(ft.output_static_array(0, 3)) mb.free_function("get_cpp_instance").call_policies = call_policies.return_value_policy( call_policies.reference_existing_object ) mb.variable("cpp_instance").exclude() cls = mb.class_("no_virtual_members_t") cls.member_function("member").add_transformation(ft.output(0)) cls = mb.class_("ft_private_destructor_t") cls.member_function("get_value").add_transformation(ft.output(0)) mb.decls(lambda decl: decl.name.startswith("_")).exclude() cls = mb.class_("bug_render_target_t") cls.mem_fun("get_statistics", arg_types=["float &"] * 2).add_transformation(ft.output(0), ft.output(1)) cls = mb.class_("modify_type_tester_t") do_nothing = cls.mem_fun("do_nothing") do_nothing.add_transformation(ft.modify_type(0, declarations.remove_reference)) clone = cls.mem_fun("clone") clone.call_policies = call_policies.return_value_policy(call_policies.manage_new_object) clone.add_transformation(ft.modify_type(0, declarations.remove_reference)) cls = mb.class_("input_c_buffer_tester_t") write_mf = cls.mem_fun("write") write_mf.add_transformation(ft.input_c_buffer("buffer", "size")) write_s = cls.mem_fun("write_s") write_s.add_transformation(ft.input_c_buffer("buffer", "size")) resource = mb.class_("resources_t") resource.held_type = "std::auto_ptr< %s >" % resource.decl_string transfer_ownership_tester = mb.class_("transfer_ownership_tester_t") tester = transfer_ownership_tester.mem_fun("tester") tester.add_transformation(ft.transfer_ownership(0)) render_queue_listener_t = mb.class_("render_queue_listener_t") render_queue_ended = render_queue_listener_t.mem_fun("render_queue_ended") render_queue_ended.add_transformation(ft.inout(2))
# generalfilereader.include() attribute = mb.class_("Attribute") attribute.include() # setAttrFuncs = attribute.member_functions('setAttributeValue') # for setAttr in setAttrFuncs: # setAttr.add_transformation(FT.input(0)) setAttrStr = attribute.mem_fun('setAttributeValue', arg_types=['::std::string &']) setAttrFloat = attribute.mem_fun('setAttributeValue', arg_types=['float &']) setAttrInt = attribute.mem_fun('setAttributeValue', arg_types=['int &']) setAttrStr.add_transformation(FT.input(0), alias='setAttrStr') setAttrFloat.add_transformation(FT.input(0), alias='setAttrFloat') setAttrInt.add_transformation(FT.input(0), alias='setAttrInt') attribute.add_property('attributeName', attribute.member_function('getAttributeName'), attribute.member_function('setAttributeName')) attribute.add_property('sValue', attribute.member_function('getAttributeString'), setAttrStr) attribute.add_property('iValue', attribute.member_function('getAttributeInt'), setAttrInt) attribute.add_property('fValue', attribute.member_function('getAttributeFloat'), setAttrFloat)