std::string PROCEDURE_TIMER::to_string(void) const { 
  std::string res;

  res = idstr_rep + ":\n";
  res += "Number of events: " + kvu_numtostr(event_count()) + "\n";
  res += "Events over bound: "  + kvu_numtostr(events_over_upper_bound());
  res += " (" + kvu_numtostr(to_seconds(&upper_bound_rep), 8) + "sec)\n";
  res += "Events under bound: "  + kvu_numtostr(events_under_lower_bound());
  res += " (" + kvu_numtostr(to_seconds(&lower_bound_rep), 8) + "sec)\n";
  res += "Min duration in seconds: " + kvu_numtostr(min_duration_seconds(), 16) + "\n";
  res += "Max duration in seconds: " + kvu_numtostr(max_duration_seconds(), 16) + "\n";
  res += "Average duration in seconds: " + kvu_numtostr(average_duration_seconds(), 16) + "\n";
  res += "Duration of last event: " + kvu_numtostr(last_duration_rep, 16) + "\n";

  return(res); 
}
예제 #2
0
bool KDLRobotModel::computeIKSearch(
    const Eigen::Affine3d& pose,
    const RobotState& start,
    RobotState& solution)
{
    // transform into kinematics and convert to kdl
    auto* T_map_kinematics = GetLinkTransform(&this->robot_state, m_kinematics_link);
    KDL::Frame frame_des;
    tf::transformEigenToKDL(T_map_kinematics->inverse() * pose, frame_des);

    // seed configuration
    for (size_t i = 0; i < start.size(); i++) {
        m_jnt_pos_in(i) = start[i];
    }

    // must be normalized for CartToJntSearch
    NormalizeAngles(this, &m_jnt_pos_in);

    auto initial_guess = m_jnt_pos_in(m_free_angle);

    auto start_time = smpl::clock::now();
    auto loop_time = 0.0;
    auto count = 0;

    auto num_positive_increments =
            (int)((GetSolverMinPosition(this, m_free_angle) - initial_guess) /
                    this->m_search_discretization);
    auto num_negative_increments =
            (int)((initial_guess - GetSolverMinPosition(this, m_free_angle)) /
                    this->m_search_discretization);

    while (loop_time < this->m_timeout) {
        if (m_ik_solver->CartToJnt(m_jnt_pos_in, frame_des, m_jnt_pos_out) >= 0) {
            NormalizeAngles(this, &m_jnt_pos_out);
            solution.resize(start.size());
            for (size_t i = 0; i < solution.size(); ++i) {
                solution[i] = m_jnt_pos_out(i);
            }
            return true;
        }
        if (!getCount(count, num_positive_increments, -num_negative_increments)) {
            return false;
        }
        m_jnt_pos_in(m_free_angle) = initial_guess + this->m_search_discretization * count;
        ROS_DEBUG("%d, %f", count, m_jnt_pos_in(m_free_angle));
        loop_time = to_seconds(smpl::clock::now() - start_time);
    }

    if (loop_time >= this->m_timeout) {
        ROS_DEBUG("IK Timed out in %f seconds", this->m_timeout);
        return false;
    } else {
        ROS_DEBUG("No IK solution was found");
        return false;
    }
    return false;
}
void PROCEDURE_TIMER::stop(void) {
  gettimeofday(&now_rep, 0);
  subtract(&now_rep, &start_rep);
  last_duration_rep = to_seconds(&now_rep);
//    cerr << idstr_rep << ": " << kvu_numtostr(length, 16) << " secs." << endl;
  events_rep++;
  event_time_total_rep += last_duration_rep;
  if (events_rep == 1) 
    memcpy(&min_event_rep, &now_rep, sizeof(struct timeval));
  if (less_than(&now_rep, &min_event_rep))
    memcpy(&min_event_rep, &now_rep, sizeof(struct timeval));
  if (less_than(&max_event_rep, &now_rep))
    memcpy(&max_event_rep, &now_rep, sizeof(struct timeval));
  if (less_than(&now_rep, &lower_bound_rep))
    events_under_bound_rep++;
  if (less_than(&upper_bound_rep, &now_rep))
    events_over_bound_rep++;
}
int main( int argc , char* argv[] )
{
	double t = Time();

	cmdLineParse( argc-1 , &argv[1] , sizeof(params)/sizeof(cmdLineReadable*) , params , 1 );
	if( Density.set ) Execute< 2 , PlyValueVertex< Real > , true  >( argc , argv );
	else              Execute< 2 ,      PlyVertex< Real > , false >( argc , argv );
#ifdef _WIN32
	if( Performance.set )
	{
		HANDLE cur_thread=GetCurrentThread();
		FILETIME tcreat, texit, tkernel, tuser;
		if( GetThreadTimes( cur_thread , &tcreat , &texit , &tkernel , &tuser ) )
			printf( "Time (Wall/User/Kernel): %.2f / %.2f / %.2f\n" , Time()-t , to_seconds( tuser ) , to_seconds( tkernel ) );
		else printf( "Time: %.2f\n" , Time()-t );
		HANDLE h = GetCurrentProcess();
		PROCESS_MEMORY_COUNTERS pmc;
		if( GetProcessMemoryInfo( h , &pmc , sizeof(pmc) ) ) printf( "Peak Memory (MB): %d\n" , pmc.PeakWorkingSetSize>>20 );
	}
예제 #5
0
파일: profiler.cpp 프로젝트: ksenglee/ros
void moveit::tools::Profiler::status(std::ostream &out, bool merge)
{
  stop();
  lock_.lock();
  printOnDestroy_ = false;

  out << std::endl;
  out << " *** Profiling statistics. Total counted time : " << to_seconds(tinfo_.total) << " seconds" << std::endl;

  if (merge)
  {
    PerThread combined;
    for (std::map<boost::thread::id, PerThread>::const_iterator it = data_.begin() ; it != data_.end() ; ++it)
    {
      for (std::map<std::string, unsigned long int>::const_iterator iev = it->second.events.begin() ; iev != it->second.events.end(); ++iev)
        combined.events[iev->first] += iev->second;
      for (std::map<std::string, AvgInfo>::const_iterator iavg = it->second.avg.begin() ; iavg != it->second.avg.end(); ++iavg)
      {
        combined.avg[iavg->first].total += iavg->second.total;
        combined.avg[iavg->first].totalSqr += iavg->second.totalSqr;
        combined.avg[iavg->first].parts += iavg->second.parts;
      }
      for (std::map<std::string, TimeInfo>::const_iterator itm = it->second.time.begin() ; itm != it->second.time.end(); ++itm)
      {
        TimeInfo &tc = combined.time[itm->first];
        tc.total = tc.total + itm->second.total;
        tc.parts = tc.parts + itm->second.parts;
        if (tc.shortest > itm->second.shortest)
          tc.shortest = itm->second.shortest;
        if (tc.longest < itm->second.longest)
          tc.longest = itm->second.longest;
      }
    }
    printThreadInfo(out, combined);
  }
  else
    for (std::map<boost::thread::id, PerThread>::const_iterator it = data_.begin() ; it != data_.end() ; ++it)
    {
      out << "Thread " << it->first << ":" << std::endl;
      printThreadInfo(out, it->second);
    }
  lock_.unlock();
}
예제 #6
0
   asset balance_record::calculate_yield( fc::time_point_sec now, share_type amount, share_type yield_pool, share_type share_supply )const
   {
      if( amount <= 0 )       return asset(0, condition.asset_id);
      if( share_supply <= 0 ) return asset(0, condition.asset_id);
      if( yield_pool <= 0 )   return asset(0, condition.asset_id);

      auto elapsed_time = (now - deposit_date);
      if( elapsed_time <= fc::seconds( BTS_BLOCKCHAIN_MIN_YIELD_PERIOD_SEC ) )
          return asset(0, condition.asset_id);

      fc::uint128 current_supply( share_supply - yield_pool );
      if( current_supply <= 0)
          return asset(0, condition.asset_id);

      fc::uint128 fee_fund( yield_pool );
      fc::uint128 amount_withdrawn( amount );
      amount_withdrawn *= 1000000;

      //
      // numerator in the following expression is at most
      // BTS_BLOCKCHAIN_MAX_SHARES * 1000000 * BTS_BLOCKCHAIN_MAX_SHARES
      // thus it cannot overflow
      //
      fc::uint128 yield = (amount_withdrawn * fee_fund) / current_supply;

      /**
       *  If less than 1 year, the 80% of yield are scaled linearly with time and 20% scaled by time^2,
       *  this should produce a yield curve that is "80% simple interest" and 20% simulating compound
       *  interest.
       */
      if( elapsed_time < fc::seconds( BTS_BLOCKCHAIN_MAX_YIELD_PERIOD_SEC ) )
      {
         fc::uint128 original_yield = yield;
         // discount the yield by 80%
         yield *= 8;
         yield /= 10;
         //
         // yield largest value in preceding multiplication is at most
         // BTS_BLOCKCHAIN_MAX_SHARES * 1000000 * BTS_BLOCKCHAIN_MAX_SHARES * 8
         // thus it cannot overflow
         //

         fc::uint128 delta_yield = original_yield - yield;

         // yield == amount withdrawn / total usd  *  fee fund * fraction_of_year
         yield *= elapsed_time.to_seconds();
         yield /= BTS_BLOCKCHAIN_MAX_YIELD_PERIOD_SEC;

         delta_yield *= elapsed_time.to_seconds();
         delta_yield /= BTS_BLOCKCHAIN_MAX_YIELD_PERIOD_SEC;

         delta_yield *= elapsed_time.to_seconds();
         delta_yield /= BTS_BLOCKCHAIN_MAX_YIELD_PERIOD_SEC;

         yield += delta_yield;
      }

      yield /= 1000000;

      if((yield > 0) && (yield < fc::uint128_t(yield_pool)))
         return asset( yield.to_uint64(), condition.asset_id );
      return asset( 0, condition.asset_id );
   }
예제 #7
0
파일: client.cpp 프로젝트: OspreyHub/ATCD
int
Paced_Worker::svc (void)
{
  try
    {
      int result =
        this->setup ();

      if (result != 0)
        return result;

      for (CORBA::ULong i = 0;
           i != this->history_.max_samples ();
           ++i)
        {
          ACE_hrtime_t deadline_for_current_call =
            this->deadline_for_current_call (i);

          ACE_hrtime_t time_before_call =
            ACE_OS::gethrtime ();

          if (time_before_call > deadline_for_current_call)
            {
              this->missed_start_deadline (i + 1);
              continue;
            }

          this->test_->method (work,
                               prime_number);

          ACE_hrtime_t time_after_call =
            ACE_OS::gethrtime ();
          this->history_.sample (time_after_call - time_before_call);

          if (time_after_call > deadline_for_current_call)
            {
              this->missed_end_deadline (i + 1);
              continue;
            }

          ACE_hrtime_t sleep_time =
            deadline_for_current_call - time_after_call;

          ACE_OS::sleep (ACE_Time_Value (0,
                                         long (to_seconds (sleep_time, gsf) *
                                               ACE_ONE_SECOND_IN_USECS)));
        }

      ACE_hrtime_t test_end = ACE_OS::gethrtime ();

      done = 1;

      end_synchronization (this->synchronizers_);

      this->print_stats (test_end);
    }
  catch (const CORBA::Exception& ex)
    {
      ex._tao_print_exception ("Exception caught:");
      return -1;
    }

  return 0;
}
예제 #8
0
파일: client.cpp 프로젝트: OspreyHub/ATCD
void
Paced_Worker::print_stats (ACE_hrtime_t test_end)
{
  ACE_GUARD (TAO_SYNCH_MUTEX,
             mon,
             this->synchronizers_.worker_lock_);

  CORBA::ULong missed_total_deadlines =
    this->missed_start_deadlines_ + this->missed_end_deadlines_;

  CORBA::ULong made_total_deadlines =
    this->history_.max_samples () - missed_total_deadlines;

  ACE_DEBUG ((LM_DEBUG,
              "\n************ Statistics for thread %t ************\n\n"));

  ACE_DEBUG ((LM_DEBUG,
              "Priority = %d/%d; Rate = %d/sec; Iterations = %d; ",
              this->CORBA_priority_,
              this->native_priority_,
              this->rate_,
              this->history_.max_samples ()));

  if (count_missed_end_deadlines)
    ACE_DEBUG ((LM_DEBUG,
                "Deadlines made/missed[start,end]/%% = %d/%d[%d,%d]/%.2f%%; Effective Rate = %.2f\n",
                made_total_deadlines,
                missed_total_deadlines,
                this->missed_start_deadlines_,
                this->missed_end_deadlines_,
                made_total_deadlines * 100 / (double) this->history_.max_samples (),
                made_total_deadlines / to_seconds (test_end - test_start, gsf)));
  else
    ACE_DEBUG ((LM_DEBUG,
                "Deadlines made/missed/%% = %d/%d/%.2f%%; Effective Rate = %.2f\n",
                made_total_deadlines,
                missed_total_deadlines,
                made_total_deadlines * 100 / (double) this->history_.max_samples (),
                made_total_deadlines / to_seconds (test_end - test_start, gsf)));


  if (do_dump_history)
    {
      this->history_.dump_samples (ACE_TEXT("HISTORY"), gsf);
    }

  ACE_Basic_Stats stats;
  this->history_.collect_basic_stats (stats);
  stats.dump_results (ACE_TEXT("Total"), gsf);

  ACE_Throughput_Stats::dump_throughput (ACE_TEXT("Total"), gsf,
                                         test_end - test_start,
                                         stats.samples_count ());

  if (print_missed_invocations)
    {
      ACE_DEBUG ((LM_DEBUG, "\nMissed start invocations are: "));

      for (CORBA::ULong j = 0;
           j != this->missed_start_deadlines_;
           ++j)
        {
          ACE_DEBUG ((LM_DEBUG,
                      "%d ",
                      this->missed_start_invocations_[j]));
        }

      ACE_DEBUG ((LM_DEBUG, "\n"));

      if (count_missed_end_deadlines)
        {
          ACE_DEBUG ((LM_DEBUG, "\nMissed end invocations are: "));

          for (CORBA::ULong j = 0;
               j != this->missed_end_deadlines_;
               ++j)
            {
              ACE_DEBUG ((LM_DEBUG,
                          "%d ",
                          this->missed_end_invocations_[j]));
            }

          ACE_DEBUG ((LM_DEBUG, "\n"));
        }
    }
}
double PROCEDURE_TIMER::min_duration_seconds(void) const { return(to_seconds(&min_event_rep)); }
예제 #10
0
파일: gps.c 프로젝트: akemnade/mumpot
static void proc_gps_gpx(struct gpsfile *gpsf,
			 void (*gpsproc)(struct nmea_pointinfo *,void *),
			 void *data)
{
  static xmlSAXHandler myhandler={
    .initialized = 1,
    .startElement = mystarthandler,
    .endElement = myendhandler,
    .characters = mycharacters
  };

  gpsf->gpsproc=gpsproc;
  gpsf->gpsproc_data=data;
  if (!gpsf->ctxt) {
    
    gpsf->ctxt = xmlCreatePushParserCtxt(&myhandler, gpsf,
					 gpsf->buf,gpsf->bufpos,
					 "gpxfile");
  } else {
    xmlParseChunk(gpsf->ctxt,gpsf->buf,gpsf->bufpos,0);
  }
  gpsf->bufpos=0;
}

static void proc_gps_nmea(struct gpsfile *gpsf,
			  void (*gpsproc)(struct nmea_pointinfo *,void *),
			  void *data)
{
  char *endp;
  if (!strncmp(gpsf->buf,"<?xml",5)) {
    gpsf->handling_procedure=proc_gps_gpx;
    proc_gps_gpx(gpsf,gpsproc,data);
    return;
  }
  while ((endp=memchr(gpsf->buf,'\n',gpsf->bufpos))) {
    int readlen;
    *endp=0;
    /* printf("gps line: %s ENDLINE\n",gpsf->buf); */
    if (strstr(gpsf->buf,"<?xml")) {
      *endp='\n';
      gpsf->handling_procedure=proc_gps_gpx;
      proc_gps_gpx(gpsf,gpsproc,data);
      return;
    }
    if (strncmp(gpsf->buf,"$GPRMC",6)==0) {
      char *fields[13];
      int numfields=my_split(gpsf->buf,fields,",",13);
      if (((numfields == 13)||(numfields == 12))&&(strlen(fields[3])>3)) {
	struct tm tm;
        time_t t;
	gpsf->curpoint.lat=to_seconds(fields[3]);
        gpsf->curpoint.lon=to_seconds(fields[5]);
        if ((fields[4])[0] == 'S')
          gpsf->curpoint.lat=-gpsf->curpoint.lat;
        if ((fields[6])[0] == 'W')
          gpsf->curpoint.lon=-gpsf->curpoint.lon;
	memset(&tm,0,sizeof(tm));
	sscanf(fields[1],"%02d%02d%02d",&tm.tm_hour,&tm.tm_min,&tm.tm_sec);
	sscanf(fields[9],"%02d%02d%02d",&tm.tm_mday,&tm.tm_mon,&tm.tm_year);
	tm.tm_mon--;
	if (tm.tm_year<70)
	  tm.tm_year+=100;
	t=gmmktime(&tm);  /* t=tm-tz */
        gpsf->curpoint.time=t;
	gpsf->curpoint.start_new=gpsf->first?1:0;
        if ((gpsf->curpoint.time-gpsf->last_fix)>20) {
          gpsf->curpoint.start_new=1; 
        }
        gpsf->last_fix=t;
        gpsf->curpoint.speed=atof(fields[7]);
	if (strlen(fields[8]))
	  gpsf->curpoint.heading=atof(fields[8]);
        else
	  gpsf->curpoint.heading=INVALID_HEADING;
	gpsf->curpoint.state=(numfields==13)?((fields[12])[0]):'?';
        gpsproc(&gpsf->curpoint,data);
	gpsf->first=0;
      }
    } else if (!strncmp(gpsf->buf,"$GPGGA",6)) {
      char *fields[15];
      int numfields=my_split(gpsf->buf,fields,",",15);
      if (numfields>8)
	gpsf->curpoint.hdop=10.0*atof(fields[8]);
    }
    endp++;
    readlen=endp-gpsf->buf;
    if (readlen != gpsf->bufpos)
      memmove(gpsf->buf,endp,gpsf->bufpos-readlen);
    gpsf->bufpos-=readlen;
  }
 
}
예제 #11
0
파일: Sender_exec.cpp 프로젝트: CCJY/ATCD
void
Worker::run (void)
{
  // Select the test protocol for these invocation.
  this->policy_manager_->set_policy_overrides (this->test_protocol_policy_,
                                               CORBA::SET_OVERRIDE);

  // Payload.
  ::Protocols::test::octets_var payload (new ::Protocols::test::octets);
  payload->length (this->message_size_);

  CORBA::Octet *buffer =
    payload->get_buffer ();

  // Not necessary but good for debugging.
  ACE_OS::memset (buffer,
                  1,
                  this->message_size_ * sizeof (CORBA::Octet));

  // Record the start time of the test.
  this->test_start_ =
    ACE_OS::gethrtime ();

  // Test with several iterations.
  for (CORBA::ULong i = 0;
       i < this->iterations_;
       ++i)
    {
      ACE_hrtime_t time_before_call = 0;
      ACE_hrtime_t deadline_for_current_call = 0;

      // For PACED and LATENCY, each sender call is individually
      // noted.
      if (this->test_type_ == ::Protocols::Sender_Controller::PACED ||
          this->test_type_ == ::Protocols::Sender_Controller::LATENCY)
        {
          time_before_call =
            ACE_OS::gethrtime ();

          // Pacing code.
          if (this->test_type_ == ::Protocols::Sender_Controller::PACED)
            {
              deadline_for_current_call =
                this->deadline_for_current_call (i);

              if (time_before_call > deadline_for_current_call)
                {
                  this->missed_start_deadline (i);
                  continue;
                }
            }
        }

      // Use oneways for PACING and THROUGHPUT.
      if (this->test_type_ == ::Protocols::Sender_Controller::PACED ||
          this->test_type_ == ::Protocols::Sender_Controller::THROUGHPUT)
        {
          this->test_->oneway_method (this->session_id_,
                                      i,
                                      payload.in ());
        }
      else
        {
          // Use twoway calls for LATENCY.
          this->test_->twoway_method (this->session_id_,
                                      i,
                                      payload.inout ());
        }

      // For PACED and LATENCY, each sender call is individually
      // noted.
      if (this->test_type_ == ::Protocols::Sender_Controller::PACED ||
          this->test_type_ == ::Protocols::Sender_Controller::LATENCY)
        {
          ACE_hrtime_t time_after_call =
            ACE_OS::gethrtime ();

          if (this->test_type_ == ::Protocols::Sender_Controller::LATENCY)
            this->history_.sample ((time_after_call - time_before_call) / 2);
          else
            this->history_.sample (time_after_call - time_before_call);

          if (this->test_type_ == ::Protocols::Sender_Controller::PACED)
            {
              if (time_after_call > deadline_for_current_call)
                {
                  this->missed_end_deadline (i);
                  continue;
                }

              ACE_hrtime_t sleep_time =
                deadline_for_current_call - time_after_call;

              ACE_OS::sleep (ACE_Time_Value (0,
                                             long (to_seconds (sleep_time, gsf) *
                                                   ACE_ONE_SECOND_IN_USECS)));
            }
        }
    }

  // This call is used to ensure that all the THROUGHPUT related data
  // has reached the server.
  if (this->test_type_ == ::Protocols::Sender_Controller::THROUGHPUT &&
      this->test_protocol_tag_ != TAO_TAG_DIOP_PROFILE)
    {
      this->test_->twoway_sync ();
    }

  // Record end time for the test.
  this->test_end_ = ACE_OS::gethrtime ();

  // Use IIOP to indicate end of test to server.
  this->policy_manager_->set_policy_overrides (this->base_protocol_policy_,
                                               CORBA::SET_OVERRIDE);

  // Tell server that the test is over.
  this->test_->end_test ();
}
예제 #12
0
파일: Sender_exec.cpp 프로젝트: CCJY/ATCD
void
Worker::print_stats (void)
{
  CORBA::ULong missed_total_deadlines =
    this->missed_start_deadlines_ + this->missed_end_deadlines_;

  CORBA::ULong made_total_deadlines =
    this->iterations_ - missed_total_deadlines;

  ACE_DEBUG ((LM_DEBUG,
              "\n************ Statistics ************\n\n"));

  //
  // Senders-side stats for PACED invocations are not too relevant
  // since we are doing one way calls.
  //
  if (this->test_type_ == ::Protocols::Sender_Controller::PACED)
    {
      ACE_DEBUG ((LM_DEBUG,
                  "Rate = %d/sec; Iterations = %d; ",
                  this->invocation_rate_,
                  this->iterations_));

      if (this->count_missed_end_deadlines_)
        ACE_DEBUG ((LM_DEBUG,
                    "Deadlines made/missed[start,end]/%% = %d/%d[%d,%d]/%.2f%%; Effective Rate = %.2f\n",
                    made_total_deadlines,
                    missed_total_deadlines,
                    this->missed_start_deadlines_,
                    this->missed_end_deadlines_,
                    made_total_deadlines * 100 / (double) this->iterations_,
                    made_total_deadlines / to_seconds (this->test_end_ - this->test_start_, gsf)));
      else
        ACE_DEBUG ((LM_DEBUG,
                    "Deadlines made/missed/%% = %d/%d/%.2f%%; Effective Rate = %.2f\n",
                    made_total_deadlines,
                    missed_total_deadlines,
                    made_total_deadlines * 100 / (double) this->iterations_,
                    made_total_deadlines / to_seconds (this->test_end_ - this->test_start_, gsf)));

      if (this->print_missed_invocations_)
        {
          ACE_DEBUG ((LM_DEBUG, "\nMissed start invocations are:\n"));

          for (CORBA::ULong j = 0;
               j < this->missed_start_deadlines_;
               ++j)
            {
              ACE_DEBUG ((LM_DEBUG,
                          "%d ",
                          this->missed_start_invocations_[j]));
            }

          ACE_DEBUG ((LM_DEBUG, "\n"));

          if (this->count_missed_end_deadlines_)
            {
              ACE_DEBUG ((LM_DEBUG, "\nMissed end invocations are:\n"));

              for (CORBA::ULong j = 0;
                   j < this->missed_end_deadlines_;
                   ++j)
                {
                  ACE_DEBUG ((LM_DEBUG,
                              "%d ",
                              this->missed_end_invocations_[j]));
                }

              ACE_DEBUG ((LM_DEBUG, "\n"));
            }
        }
    }

  // Individual calls are relevant for the PACED and LATENCY tests.
  if (this->test_type_ == ::Protocols::Sender_Controller::PACED ||
      this->test_type_ == ::Protocols::Sender_Controller::LATENCY)
    {
      if (this->do_dump_history_)
        {
          this->history_.dump_samples (ACE_TEXT("HISTORY"), gsf);
        }

      ACE_Basic_Stats stats;
      this->history_.collect_basic_stats (stats);
      stats.dump_results (ACE_TEXT("Total"), gsf);

      ACE_Throughput_Stats::dump_throughput (ACE_TEXT("Total"), gsf,
                                             this->test_end_ - this->test_start_,
                                             this->iterations_);
    }
  else
    {
      ACE_hrtime_t elapsed_time =
        this->test_end_ - this->test_start_;

      double seconds =
        to_seconds (elapsed_time, gsf);

      ACE_hrtime_t bits = this->iterations_;
      bits *= this->message_size_ * 8;

      ACE_DEBUG ((LM_DEBUG,
                  "%Q bits sent in %5.1f seconds at a rate of %5.2f Mbps\n",
                  bits,
                  seconds,
                  bits / seconds / 1000 / 1000));
    }
}
예제 #13
0
bool Time::operator>(const Time& other) const
{
    return to_seconds() > other.to_seconds();
}
예제 #14
0
bool Time::operator==(const Time& other) const
{
    return (fabs(to_seconds() - other.to_seconds()) < DBL_MIN);
}
예제 #15
0
파일: profiler.cpp 프로젝트: ksenglee/ros
void moveit::tools::Profiler::printThreadInfo(std::ostream &out, const PerThread &data)
{
  double total = to_seconds(tinfo_.total);

  std::vector<dataIntVal> events;
  for (std::map<std::string, unsigned long int>::const_iterator iev = data.events.begin() ; iev != data.events.end() ; ++iev)
  {
    dataIntVal next = {iev->first, iev->second};
    events.push_back(next);
  }
  std::sort(events.begin(), events.end(), SortIntByValue());
  if (!events.empty())
    out << "Events:" << std::endl;
  for (unsigned int i = 0 ; i < events.size() ; ++i)
    out << events[i].name << ": " << events[i].value << std::endl;

  std::vector<dataDoubleVal> avg;
  for (std::map<std::string, AvgInfo>::const_iterator ia = data.avg.begin() ; ia != data.avg.end() ; ++ia)
  {
    dataDoubleVal next = {ia->first, ia->second.total / (double)ia->second.parts};
    avg.push_back(next);
  }
  std::sort(avg.begin(), avg.end(), SortDoubleByValue());
  if (!avg.empty())
    out << "Averages:" << std::endl;
  for (unsigned int i = 0 ; i < avg.size() ; ++i)
  {
    const AvgInfo &a = data.avg.find(avg[i].name)->second;
    out << avg[i].name << ": " << avg[i].value << " (stddev = " <<
      sqrt(fabs(a.totalSqr - (double)a.parts * avg[i].value * avg[i].value) / ((double)a.parts - 1.)) << ")" << std::endl;
  }

  std::vector<dataDoubleVal> time;

  for (std::map<std::string, TimeInfo>::const_iterator itm = data.time.begin() ; itm != data.time.end() ; ++itm)
  {
    dataDoubleVal next = {itm->first, to_seconds(itm->second.total)};
    time.push_back(next);
  }

  std::sort(time.begin(), time.end(), SortDoubleByValue());
  if (!time.empty())
    out << "Blocks of time:" << std::endl;

  double unaccounted = total;
  for (unsigned int i = 0 ; i < time.size() ; ++i)
  {
    const TimeInfo &d = data.time.find(time[i].name)->second;

    double tS = to_seconds(d.shortest);
    double tL = to_seconds(d.longest);
    out << time[i].name << ": " << time[i].value << "s (" << (100.0 * time[i].value/total) << "%), ["
        << tS << "s --> " << tL << " s], " << d.parts << " parts";
    if (d.parts > 0)
    {
      double pavg = to_seconds(d.total) / (double)d.parts;
      out << ", " << pavg << " s on average";
      if (pavg < 1.0)
        out << " (" << 1.0/pavg << " /s)";
    }
    out << std::endl;
    unaccounted -= time[i].value;
  }
  // if we do not appear to have counted time multiple times, print the unaccounted time too
  if (unaccounted >= 0.0)
  {
    out << "Unaccounted time : " << unaccounted;
    if (total > 0.0)
      out << " (" << (100.0 * unaccounted / total) << " %)";
    out << std::endl;
  }

  out << std::endl;
}