PathPlannerSVC_impl.h
Go to the documentation of this file.
00001 // -*-C++-*-
00007 #ifndef PATHPLANNERSVC_IMPL_H
00008 #define PATHPLANNERSVC_IMPL_H
00009 
00010 #include <rtm/RTC.h>
00011 #include <map>
00012 #include <hrpCorba/PathPlanner.hh>
00013 #include <hrpPlanner/PathPlanner.h>
00014  
00015 /*
00016  * Example class implementing IDL interface OpenHRP::PathPlanner
00017  */
00018 class OpenHRP_PathPlannerSVC_impl
00019     : public virtual POA_OpenHRP::PathPlanner,
00020       public virtual PortableServer::RefCountServantBase
00021 {
00022 private:
00023     // Make sure all instances are built on the heap by making the
00024     // destructor non-public
00025     //virtual ~OpenHRP_PathPlannerSVC_impl();
00026 
00030     PathEngine::PathPlanner* path_;
00031 
00035     std::string nameServer_;
00036 
00037 public:
00038     // standard constructor
00039     OpenHRP_PathPlannerSVC_impl();
00040     virtual ~OpenHRP_PathPlannerSVC_impl();
00041 
00042     // attributes and operations
00043     void stopPlanning();
00044     void getRoadmap(OpenHRP::PathPlanner::Roadmap_out graph);
00045     void clearRoadmap();
00046     void getMobilityNames(OpenHRP::StringSequence_out mobilities);
00047     void getOptimizerNames(OpenHRP::StringSequence_out optimizers);
00048     void setRobotName(const char* model);
00049     void setAlgorithmName(const char* algorithm);
00050     bool setMobilityName(const char* mobility);
00051     void getAlgorithmNames(OpenHRP::StringSequence_out algos);
00052     bool getProperties(const char* alg, OpenHRP::StringSequence_out props, OpenHRP::StringSequence_out defaults);
00053     void initPlanner();
00054     void setStartPosition(CORBA::Double x, CORBA::Double y, CORBA::Double theta);
00055     void setGoalPosition(CORBA::Double x, CORBA::Double y, CORBA::Double theta);
00056     void setProperties(const OpenHRP::PathPlanner::Property& properites);
00057     CORBA::Boolean calcPath();
00058     void getPath(OpenHRP::PathPlanner::PointArray_out path);
00059     CORBA::Boolean optimize(const char *optimizer);
00060     void registerIntersectionCheckPair(const char* char1, const char* name1, const char* char2, const char* name2, CORBA::Double tolerance);
00061     void registerCharacter(const char* name, OpenHRP::BodyInfo_ptr cInfo);
00062     void registerCharacterByURL(const char* name, const char* url);
00063     void setCharacterPosition(const char* character,
00064                               const OpenHRP::DblSequence& pos); 
00065     void initSimulation();
00066     void setNameServer(std::string nameServer) {nameServer_ = nameServer;}
00067 
00068 };
00069 
00070 
00071 
00072 #endif // PATHPLANNERSVC_IMPL_H
00073 
00074 


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Thu Apr 11 2019 03:30:18