4 #include <rtm/DataFlowComponentBase.h>    11                std::vector<hrp::ColdetLinkPairPtr> &pairs)
    25     for (std::map<std::string, ModelItem>::iterator it=prj.
models().begin();
    26          it != prj.
models().end(); it++){
    27         const std::string 
name    28             = it->second.rtcName == 
"" ? it->first : it->second.rtcName; 
    62         if(bodyIndex1 >= 0 && bodyIndex2 >= 0){
    66             std::vector<hrp::Link*> links1;
    70                 std::copy(traverse.
begin(), traverse.
end(), links1.begin());
    72                 links1.push_back(bodyPtr1->link(cpi.
jointName1));
    75             std::vector<hrp::Link*> links2;
    79                 std::copy(traverse.
begin(), traverse.
end(), links2.begin());
    81                 links2.push_back(bodyPtr2->link(cpi.
jointName2));
    84             for(
size_t j=0; 
j < links1.size(); ++
j){
    85                 for(
size_t k=0; k < links2.size(); ++k){
    89                     if(link1 && link2 && link1 != link2 
    92                             (bodyIndex1, link1, bodyIndex2, link2, 
   121         if(bodyIndex1 >= 0 && bodyIndex2 >= 0){
   139                     bodyIndex1, link1, bodyIndex2, link2, 
   149     for(
int i=0; 
i < nBodies; ++
i){
   151         bodyPtr->initializeConfiguration();
   154     for (std::map<std::string, ModelItem>::iterator it=prj.
models().begin();
   155          it != prj.
models().end(); it++){
   157         if (it->second.rtcName != 
"") body = world.
body(it->second.rtcName);
   158         if (!body) body = world.
body(it->first);
   160             std::cerr << 
"can't find a body named " << it->first << 
" or "   161                       << it->second.rtcName << std::endl;
   164         for (std::map<std::string, JointItem>::iterator it2=it->second.joint.begin();
   165              it2 != it->second.joint.end(); it2++){
   166             hrp::Link *link = body->link(it2->first);
   169                 link->
p = it2->second.translation;
   171                 link->
v = it2->second.linearVelocity;
   172                 link->
w = it2->second.angularVelocity;
   173                 link->
vo = link->
v - link->
w.cross(link->
p);
   175                 link->
q = it2->second.angle;
   178         body->calcForwardKinematics();
   179         body->setDefaultRootPosition(body->rootLink()->p, body->rootLink()->attitude());
   193     for (std::map<std::string, RTSItem::rtc>::iterator it 
   195         std::string 
path = it->second.path;
   196         if (path == 
"") 
continue;
   202         std::cout << 
"loading " << path << std::endl; 
   203         std::string initfunc = it->second.name + 
"Init";
   204         manager.
load(path.c_str(), initfunc.c_str());
   207     for (std::map<std::string, RTSItem::rtc>::iterator it 
   211             if (it->second.name == 
""){
   212                 std::cerr << 
"factory name for " << it->first << 
" is not defined" << std::endl;
   215             std::cout << 
"creating " << it->first << std::endl;
   216             std::string args = it->second.name + 
"?instance_name=" + it->first;
   220             std::cerr << 
"failed to create RTC(" << it->first << 
")" << std::endl;
   224         for(CORBA::ULong 
i=0; 
i < eclist->length(); ++
i){
   225             if(!CORBA::is_nil(eclist[
i])){
   226                 OpenRTM::ExtTrigExecutionContextService_var execContext = OpenRTM::ExtTrigExecutionContextService::_narrow(eclist[i]);
   227                 if(!CORBA::is_nil(execContext)){
   228                     std::cout << it->first << 
":" << it->second.period << std::endl;
   229                     receivers.push_back(
ClockReceiver(execContext, it->second.period));
   230                     execContext->activate_component(rtc->
getObjRef());
   236             RTC::RTObject_var rtc = 
findRTC(it->first);
   237             for (
size_t i=0; 
i<it->second.configuration.size(); 
i++){
   239                                  it->second.configuration[
i].second);
   244     for (std::vector<std::pair<std::string, std::string> >::iterator it
   246         std::cout << 
"making a connection between "   247                   << it->first << 
" and " << it->second << std::endl;
   248         int pos1 = it->first.find(
'.');
   249         std::string comp1 = it->first.substr(0, pos1);
   250         std::string port1 = it->first;
   251         int pos2 = it->second.find(
'.');
   252         std::string comp2 = it->second.substr(0, pos2);
   253         std::string port2 = it->second;
   257             std::cerr << 
"can't find a component named " << comp1 << std::endl;
   262             std::cerr << 
"can't find a component named " << comp2 << std::endl;
   265         RTC::PortServiceList_var ports1 = rtc1->get_ports();
   266         RTC::PortServiceList_var ports2 = rtc2->get_ports();
   268         RTC::PortService_ptr portObj1=NULL, portObj2=NULL; 
   269         for(CORBA::ULong 
i = 0; 
i < ports1->length(); ++
i ){
   270             RTC::PortProfile_var 
profile = ports1[
i]->get_port_profile();
   271             std::string portName(profile->name);
   272             if (portName == port1){
   273                 portObj1 = ports1[
i];
   278             std::cerr << 
"can't find a port named " << port1 << std::endl;
   281         for(CORBA::ULong 
i = 0; 
i < ports2->length(); ++
i ){
   282             RTC::PortProfile_var 
profile = ports2[
i]->get_port_profile();
   283             std::string portName(profile->name);
   284             if (portName == port2){
   285                 portObj2 = ports2[
i];
   290             std::cerr << 
"can't find a port named " << port2 << std::endl;
 std::map< std::string, rtc > components
png_infop png_charpp int png_charpp profile
std::vector< ExtraJointItem > & extraJoints()
RTObject_impl * createComponent(const char *comp_args)
bool addExtraJoint(int bodyIndex1, Link *link1, int bodyIndex2, Link *link2, const double *link1LocalPos, const double *link2LocalPos, const short jointType, const double *jointAxis)
int bodyIndex(const std::string &name)
std::vector< Link * >::const_iterator end() const 
int addBody(BodyPtr body)
void useBuiltinCollisionDetector(bool on)
def findRTC(name, rnc=None)
get RT component 
virtual void initialize()
void clearCollisionCheckLinkPairs()
RTObject_impl * getComponent(const char *instance_name)
png_infop png_charpp name
void setCurrentTime(double tm)
void load(const char *fname, const char *initfunc)
void setAttitude(const Matrix33 &R)
std::vector< Link * >::const_iterator begin() const 
static Manager & instance()
void setRungeKuttaMethod()
unsigned int numLinks() const 
def setConfiguration(rtc, nvlist)
update default configuration set 
def j(str, encoding="cp932")
std::map< std::string, ModelItem > & models()
def connectPorts(outP, inPs, subscription="flush", dataflow="Push", bufferlength=1, rate=1000)
connect ports 
bool addCollisionCheckLinkPair(int bodyIndex1, Link *link1, int bodyIndex2, Link *link2, double muStatic, double muDynamic, double culling_thresh, double restitution, double epsilon)
const char * getInstanceName()
virtual ExecutionContextList * get_owned_contexts()
void initRTS(Project &prj, std::vector< ClockReceiver > &receivers)
TConstraintForceSolver constraintForceSolver
std::vector< std::pair< std::string, std::string > > connections
void setTimeStep(double dt)
void setInstanceName(const char *instance_name)
void enableSensors(bool on)
boost::function2< hrp::BodyPtr, const std::string &, const ModelItem & > BodyFactory
RTObject_ptr getObjRef() const 
void initWorld(Project &prj, BodyFactory &factory, hrp::World< hrp::ConstraintForceSolver > &world, std::vector< hrp::ColdetLinkPairPtr > &pairs)
std::vector< CollisionPairItem > & collisionPairs()