/*!

 */
Strategy::BallArea
Strategy::get_ball_area( const WorldModel & wm )
{
    int ball_step = 1000;
    ball_step = std::min( ball_step, wm.interceptTable()->teammateReachCycle() );
    ball_step = std::min( ball_step, wm.interceptTable()->opponentReachCycle() );
    ball_step = std::min( ball_step, wm.interceptTable()->selfReachCycle() );

    return get_ball_area( wm.ball().inertiaPoint( ball_step ) );
}
/*!

 */
Vector2D
Bhv_ChainAction::getKeepBallVel( const WorldModel & wm )
{
    static GameTime s_update_time( 0, 0 );
    static Vector2D s_best_ball_vel( 0.0, 0.0 );

    if ( s_update_time == wm.time() )
    {
        return s_best_ball_vel;
    }
    s_update_time = wm.time();

    //
    //
    //

    const int ANGLE_DIVS = 12;

    const ServerParam & SP = ServerParam::i();
    const PlayerType & ptype = wm.self().playerType();
    const double collide_dist2 = std::pow( ptype.playerSize()
                                           + SP.ballSize(),
                                           2 );
    const double keep_dist = ptype.playerSize()
        + ptype.kickableMargin() * 0.5
        + ServerParam::i().ballSize();

    const Vector2D next_self_pos
        = wm.self().pos() + wm.self().vel();
    const Vector2D next2_self_pos
        = next_self_pos
        + wm.self().vel() * ptype.playerDecay();

    //
    // create keep target point
    //

    Vector2D best_ball_vel = Vector2D::INVALIDATED;
    int best_opponent_step = 0;
    double best_ball_speed = 1000.0;


    for ( int a = 0; a < ANGLE_DIVS; ++a )
    {
        Vector2D keep_pos
            = next2_self_pos
            + Vector2D::from_polar( keep_dist,
                                    360.0/ANGLE_DIVS * a );
        if ( keep_pos.absX() > SP.pitchHalfLength() - 0.2
             || keep_pos.absY() > SP.pitchHalfWidth() - 0.2 )
        {
            continue;
        }

        Vector2D ball_move = keep_pos - wm.ball().pos();
        double ball_speed = ball_move.r() / ( 1.0 + SP.ballDecay() );

        Vector2D max_vel
            = KickTable::calc_max_velocity( ball_move.th(),
                                            wm.self().kickRate(),
                                            wm.ball().vel() );
        if ( max_vel.r2() < std::pow( ball_speed, 2 ) )
        {
            continue;
        }

        Vector2D ball_next_next = keep_pos;

        Vector2D ball_vel = ball_move.setLengthVector( ball_speed );
        Vector2D ball_next = wm.ball().pos() + ball_vel;

        if ( next_self_pos.dist2( ball_next ) < collide_dist2 )
        {
            ball_next_next = ball_next;
            ball_next_next += ball_vel * ( SP.ballDecay() * -0.1 );
        }

#ifdef DEBUG_PRINT
        dlog.addText( Logger::TEAM,
                      __FILE__": (getKeepBallVel) %d: ball_move th=%.1f speed=%.2f max=%.2f",
                      a,
                      ball_move.th().degree(),
                      ball_speed,
                      max_vel.r() );
        dlog.addText( Logger::TEAM,
                      __FILE__": __ ball_next=(%.2f %.2f) ball_next2=(%.2f %.2f)",
                      ball_next.x, ball_next.y,
                      ball_next_next.x, ball_next_next.y );
#endif

        //
        // check opponent
        //

        int min_step = 1000;
        for ( PlayerPtrCont::const_iterator o = wm.opponentsFromSelf().begin();
              o != wm.opponentsFromSelf().end();
              ++o )
        {
            if ( (*o)->distFromSelf() > 10.0 )
            {
                break;
            }

            int o_step = FieldAnalyzer::predict_player_reach_cycle( *o,
                                                                    ball_next_next,
                                                                    (*o)->playerTypePtr()->kickableArea(),
                                                                    0.0, // penalty distance
                                                                    1, // body count thr
                                                                    1, // default turn step
                                                                    0, // wait cycle
                                                                    true );

            if ( o_step <= 0 )
            {
                break;
            }

            if ( o_step < min_step )
            {
                min_step = o_step;
            }
        }
#ifdef DEBUG_PRINT
        dlog.addText( Logger::TEAM,
                      __FILE__": (getKeepBallVel) %d: keepPos=(%.2f %.2f)"
                      " ballNext2=(%.2f %.2f) ballVel=(%.2f %.2f) speed=%.2f o_step=%d",
                      a,
                      keep_pos.x, keep_pos.y,
                      ball_next_next.x, ball_next_next.y,
                      ball_vel.x, ball_vel.y,
                      ball_speed,
                      min_step );
#endif
        if ( min_step > best_opponent_step )
        {
            best_ball_vel = ball_vel;
            best_opponent_step = min_step;
            best_ball_speed = ball_speed;
        }
        else if ( min_step == best_opponent_step )
        {
            if ( best_ball_speed > ball_speed )
            {
                best_ball_vel = ball_vel;
                best_opponent_step = min_step;
                best_ball_speed = ball_speed;
            }
        }
    }

    s_best_ball_vel = best_ball_vel;
    return s_best_ball_vel;
}
/*!

 */
void
PredictState::init( const WorldModel & wm )
{
    //
    // initialize world
    //
    M_world = &wm;

    //
    // initialize spend_time
    //
    M_spend_time = 0;

    //
    // initialize ball pos & vel
    //
    M_ball.assign( wm.ball().pos(), wm.ball().vel() );

    //
    // initialize self_unum
    //
    M_self_unum = wm.self().unum();

    //
    // initialize ball holder
    //
    const AbstractPlayerObject * h = wm.getTeammateNearestToBall( VALID_PLAYER_THRESHOLD );

    if ( h
         && wm.ball().pos().dist2( h->pos() ) < wm.ball().pos().dist2( wm.self().pos() ) )
    {
        M_ball_holder_unum = h->unum();
    }
    else
    {
        M_ball_holder_unum = wm.self().unum();
    }

    //
    // initialize all teammates
    //
    M_our_players.reserve( 11 );

    for ( int n = 1; n <= 11; ++n )
    {
        PredictPlayerObject::Ptr ptr;

        if ( n == M_self_unum )
        {
            ptr = PredictPlayerObject::Ptr( new PredictPlayerObject( wm.self() ) );
        }
        else
        {
            const AbstractPlayerObject * t = wm.ourPlayer( n );

            if ( t )
            {
                ptr = PredictPlayerObject::Ptr( new PredictPlayerObject( *t ) );

            }
            else
            {
                ptr = PredictPlayerObject::Ptr( new PredictPlayerObject() );
            }
        }

        M_our_players.push_back( ptr );

#ifndef STRICT_LINE_UPDATE
        if ( ptr->isValid()
             && M_our_offense_player_line_x < ptr->pos().x )
        {
            M_our_offense_player_line_x = ptr->pos().x;
        }
#endif
    }

    updateLines();
}
Exemple #4
0
/*!

 */
void
ShootGenerator::createShoot( const WorldModel & wm,
                             const Vector2D & target_point )
{
    const AngleDeg ball_move_angle = ( target_point - M_first_ball_pos ).th();

    const PlayerObject * goalie = wm.getOpponentGoalie();
    if ( goalie
         && 5 < goalie->posCount()
         && goalie->posCount() < 30
         && wm.dirCount( ball_move_angle ) > 3 )
    {
#ifdef DEBUG_PRINT
        dlog.addText( Logger::SHOOT,
                      "%d: __ xxx goalie_count=%d, low dir accuracy",
                      M_total_count,
                      goalie->posCount() );
#endif
        return;
    }

    const ServerParam & SP = ServerParam::i();

    const double ball_speed_max = ( wm.gameMode().type() == GameMode::PlayOn
                                    || wm.gameMode().isPenaltyKickMode()
                                    ? SP.ballSpeedMax()
                                    : wm.self().kickRate() * SP.maxPower() );

    const double ball_move_dist = M_first_ball_pos.dist( target_point );

    const Vector2D max_one_step_vel
        = ( wm.self().isKickable()
            ? KickTable::calc_max_velocity( ball_move_angle,
                                            wm.self().kickRate(),
                                            wm.ball().vel() )
            : ( target_point - M_first_ball_pos ).setLengthVector( 0.1 ) );
    const double max_one_step_speed = max_one_step_vel.r();

    double first_ball_speed
        = std::max( ( ball_move_dist + 5.0 ) * ( 1.0 - SP.ballDecay() ),
                    std::max( max_one_step_speed,
                              1.5 ) );

    bool over_max = false;
#ifdef DEBUG_PRINT_FAILED_COURSE
    bool success = false;
#endif
    while ( ! over_max )
    {
        if ( first_ball_speed > ball_speed_max - 0.001 )
        {
            over_max = true;
            first_ball_speed = ball_speed_max;
        }

        if ( createShoot( wm,
                          target_point,
                          first_ball_speed,
                          ball_move_angle,
                          ball_move_dist ) )
        {
            Course & course = M_courses.back();

            if ( first_ball_speed <= max_one_step_speed + 0.001 )
            {
                course.kick_step_ = 1;
            }

#ifdef DEBUG_PRINT_SUCCESS_COURSE
            dlog.addText( Logger::SHOOT,
                          "%d: ok shoot target=(%.2f %.2f)"
                          " speed=%.3f angle=%.1f",
                          M_total_count,
                          target_point.x, target_point.y,
                          first_ball_speed,
                          ball_move_angle.degree() );
            dlog.addRect( Logger::SHOOT,
                          target_point.x - 0.1, target_point.y - 0.1,
                          0.2, 0.2,
                          "#00ff00" );
            char num[8];
            snprintf( num, 8, "%d", M_total_count );
            dlog.addMessage( Logger::SHOOT,
                             target_point, num, "#ffffff" );
#endif
#ifdef DEBUG_PRINT_FAILED_COURSE
            success = true;
#endif
#ifdef SEARCH_UNTIL_MAX_SPEED_AT_SAME_POINT
            if ( course.goalie_never_reach_
                 && course.opponent_never_reach_ )
            {
                return;
            }
            ++M_total_count;
#else
            return;
#endif
        }

        first_ball_speed += 0.3;
    }

#ifdef DEBUG_PRINT_FAILED_COURSE
    if ( success )
    {
        return;
    }

    dlog.addText( Logger::SHOOT,
                  "%d: xxx shoot target=(%.2f %.2f)"
                  " speed=%.3f angle=%.1f",
                  M_total_count,
                  target_point.x, target_point.y,
                  first_ball_speed,
                  ball_move_angle.degree() );
    dlog.addRect( Logger::SHOOT,
                  target_point.x - 0.1, target_point.y - 0.1,
                  0.2, 0.2,
                  "#ff0000" );
    char num[8];
    snprintf( num, 8, "%d", M_total_count );
    dlog.addMessage( Logger::SHOOT,
                     target_point, num, "#ffffff" );
#endif
}
Exemple #5
0
/*!

 */
void
ShootGenerator::generate( const WorldModel & wm, bool consider_shot_distance )
{
#ifdef __APPLE__
    static GameTime s_update_time( 0, 0 );
#else
    static thread_local GameTime s_update_time( 0, 0 );
#endif

    if ( s_update_time == wm.time() )
    {
        return;
    }
    s_update_time = wm.time();

    clear();

    if ( ! wm.self().isKickable()
         && wm.interceptTable()->selfReachCycle() > 1 )
    {
        return;
    }

    if ( wm.time().stopped() > 0
         || wm.gameMode().type() == GameMode::KickOff_
         // || wm.gameMode().type() == GameMode::KickIn_
         || wm.gameMode().type() == GameMode::IndFreeKick_ )
    {
        return;
    }

    const ServerParam & SP = ServerParam::i();

    if ( consider_shot_distance &&
         wm.self().pos().dist2( SP.theirTeamGoalPos() ) > std::pow( 30.0, 2 ) )
    {
#ifdef DEBUG_PRINT
      dlog.addText( Logger::SHOOT,
                    __FILE__": over shootable distance" );
#endif
      return;
    }

    M_first_ball_pos = ( wm.self().isKickable()
                         ? wm.ball().pos()
                         : wm.ball().pos() + wm.ball().vel() );

#ifdef DEBUG_PROFILE
    MSecTimer timer;
#endif

    Vector2D goal_l( SP.pitchHalfLength(), -SP.goalHalfWidth() );
    Vector2D goal_r( SP.pitchHalfLength(), +SP.goalHalfWidth() );

    goal_l.y += std::min( 1.5,
                          0.6 + goal_l.dist( M_first_ball_pos ) * 0.042 );
    goal_r.y -= std::min( 1.5,
                          0.6 + goal_r.dist( M_first_ball_pos ) * 0.042 );

    if ( wm.self().pos().x > SP.pitchHalfLength() - 1.0
         && wm.self().pos().absY() < SP.goalHalfWidth() )
    {
        goal_l.x = wm.self().pos().x + 1.5;
        goal_r.x = wm.self().pos().x + 1.5;
    }

    const int DIST_DIVS = 25;
    const double dist_step = std::fabs( goal_l.y - goal_r.y ) / ( DIST_DIVS - 1 );

#ifdef DEBUG_PRINT
    dlog.addText( Logger::SHOOT,
                  __FILE__": ===== Shoot search range=(%.1f %.1f)-(%.1f %.1f) dist_step=%.1f =====",
                  goal_l.x, goal_l.y, goal_r.x, goal_r.y, dist_step );
#endif

    for ( int i = 0; i < DIST_DIVS; ++i )
    {
        ++M_total_count;

        Vector2D target_point = goal_l;
        target_point.y += dist_step * i;

#ifdef DEBUG_PRINT
        dlog.addText( Logger::SHOOT,
                      "%d: ===== shoot target(%.2f %.2f) ===== ",
                      M_total_count,
                      target_point.x, target_point.y );
#endif
        createShoot( wm, target_point );
    }


    evaluateCourses( wm );


#ifdef DEBUG_PROFILE
    dlog.addText( Logger::SHOOT,
                  __FILE__": PROFILE %d/%d. elapsed=%.3f [ms]",
                  (int)M_courses.size(),
                  DIST_DIVS,
                  timer.elapsedReal() );
#endif

}
/*!

*/
double
Neck_ScanPlayers::calculate_score( const WorldModel & wm,
                                   const Vector2D & next_self_pos,
                                   const AngleDeg & left_angle,
                                   const AngleDeg & right_angle )
{
    double score = 0.0;
    double view_buffer = 90.0;

    const int our_min = std::min( wm.interceptTable()->selfReachCycle(),
                                  wm.interceptTable()->teammateReachCycle() );
    const int opp_min = wm.interceptTable()->opponentReachCycle();
    const bool our_ball = ( our_min <= opp_min );

    const AbstractPlayerCont::const_iterator end = wm.allPlayers().end();
    for ( AbstractPlayerCont::const_iterator p = wm.allPlayers().begin();
          p != end;
          ++p )
    {
        if ( (*p)->isSelf() ) continue;

        Vector2D pos = (*p)->pos() + (*p)->vel();
        AngleDeg angle = ( pos - next_self_pos ).th();

        if ( ! angle.isRightOf( left_angle )
             || ! angle.isLeftOf( right_angle ) )
        {
            continue;
        }

        double pos_count = (*p)->seenPosCount();
        if ( (*p)->isGhost()
             && (*p)->ghostCount() % 2 == 1 )
        {
            pos_count = std::min( 2.0, pos_count );
        }
        pos_count += 1.0;

        if ( our_ball )
        {
            if ( (*p)->side() == wm.ourSide()
                 && ( (*p)->pos().x > wm.ball().pos().x - 10.0
                      || (*p)->pos().x > 30.0 ) )
            {
                pos_count *= 2.0;
            }
        }

        double base_val = std::pow( pos_count, 2 );
        double rate = std::exp( - std::pow( (*p)->distFromSelf(), 2 )
                                / ( 2.0 * std::pow( 20.0, 2 ) ) ); // Magic Number
        score += base_val * rate;

        double buf = std::min( ( angle - left_angle ).abs(),
                               ( angle - right_angle ).abs() );
#ifdef DEBUG_PRINT
        dlog.addText( Logger::ACTION,
                      "__ %c_%d (%.2f %.2f) count=%d base=%f rate=%f +%f buf=%.1f",
                      (*p)->side() == LEFT ? 'L' : (*p)->side() == RIGHT ? 'R' : 'N',
                      (*p)->unum(),
                      (*p)->pos().x, (*p)->pos().y,
                      (*p)->posCount(),
                      base_val, rate, base_val * rate,
                      buf );
#endif

        if ( buf < view_buffer )
        {
            view_buffer = buf;
        }
    }

    // The bigger view buffer, the bigger rate
    // range: [1.0:2.0]
    // double rate = 2.0 - std::exp( - std::pow( view_buffer, 2 )
    //                               / ( 2.0 * std::pow( 180.0, 2 ) ) ); // Magic Number
    double rate = 1.0 + view_buffer / 90.0;
#ifdef DEBUG_PRINT
    dlog.addText( Logger::ACTION,
                  "base_score=%.1f view_buf=%.1f rate=%f -> %f",
                  score,
                  view_buffer,
                  rate,
                  score * rate );
#endif

    score *= rate;

    return score;

}
void
FullstateSensor::printWithWorld( const WorldModel & world ) const
{
    Vector2D tmpv;
    double tmpval;
    dlog.addText( Logger::WORLD,
                  "FS ball    (%+.3f %+.3f) (%+.3f %+.3f) %.3f",
                  ball().pos_.x, ball().pos_.y,
                  ball().vel_.x, ball().vel_.y,
                  ball().vel_.r() );
    dlog.addText( Logger::WORLD,
                  "____internal (%+.3f %+.3f) (%+.3f %+.3f) %.3f  gconf=%d rconf=%d",
                  world.ball().pos().x, world.ball().pos().y,
                  world.ball().vel().x, world.ball().vel().y,
                  world.ball().vel().r(),
                  world.ball().posCount(), world.ball().rposCount() );
    tmpv = ball().pos_ - world.ball().pos();
    dlog.addText( Logger::WORLD,
                  "__ball pos err (%+.3f %+.3f) %.3f",
                  tmpv.x, tmpv.y, tmpv.r() );
    dlog.addText( Logger::WORLD,
                  "____internal (%+.3f %+.3f)",
                  world.ball().posError().x, world.ball().posError().y );
    tmpv = ball().vel_ - world.ball().vel();
    tmpval = tmpv.r();
    dlog.addText( Logger::WORLD,
                  "__ball vel err (%+.3f %+.3f) %.3f  %s",
                  tmpv.x, tmpv.y, tmpval, (tmpval > 1.0 ? "big error" : "" ) );
    dlog.addText( Logger::WORLD,
                  "____internal (%+.3f %+.3f)",
                  world.ball().velError().x, world.ball().velError().y );

    const FullstateSensor::PlayerCont& player_cont
        = ( world.isOurLeft()
            ? leftTeam()
            : rightTeam() );
    for ( FullstateSensor::PlayerCont::const_iterator it = player_cont.begin();
          it != player_cont.end();
          ++it )
    {
        if ( it->unum_ == world.self().unum() )
        {
            dlog.addText( Logger::WORLD,
                          "FS self  (%+.3f %+.3f) (%+.3f %+.3f) b=%+.2f n=%+.2f f=%+.2f",
                          it->pos_.x, it->pos_.y,
                          it->vel_.x, it->vel_.y,
                          it->body_, it->neck_,
                          AngleDeg::normalize_angle( it->body_ + it->neck_ ) );

            dlog.addText( Logger::WORLD,
                          "____internal (%+.3f %+.3f) (%+.3f %+.3f) b=%+.2f n=%+.2f f=%+.2f",
                          world.self().pos().x, world.self().pos().y,
                          world.self().vel().x, world.self().vel().y,
                          world.self().body().degree(),
                          world.self().neck().degree(),
                          world.self().face().degree() );

            tmpv = it->pos_ - world.self().pos();
            double d = tmpv.r();
            dlog.addText( Logger::WORLD,
                          "__self pos err (%+.3f %+.3f) %.3f %s",
                          tmpv.x, tmpv.y, d, ( d > 0.3 ? "  big error" : "" ) );
            dlog.addText( Logger::WORLD,
                          "____internal (%+.3f %+.3f) %.3f",
                          world.self().posError().x,
                          world.self().posError().y,
                          world.self().posError().r() );
            tmpv = it->vel_ - world.self().vel();
            dlog.addText( Logger::WORLD,
                          "__self vel err (%+.3f %+.3f) %.3f",
                          tmpv.x, tmpv.y, tmpv.r() );
            dlog.addText( Logger::WORLD,
                          "____internal (%+.3f %+.3f) %.3f",
                          world.self().velError().x,
                          world.self().velError().y,
                          world.self().velError().r() );
            tmpv = ball().pos_ - it->pos_;
            dlog.addText( Logger::WORLD,
                          "__ball rpos (%+.3f %+.3f) %.3f",
                          tmpv.x, tmpv.y, tmpv.r() );
            dlog.addText( Logger::WORLD,
                          "____internal (%+.3f %+.3f) %.3f",
                          world.ball().rpos().x,
                          world.ball().rpos().y,
                          world.ball().rpos().r() );
            tmpv -= world.ball().rpos();
            dlog.addText( Logger::WORLD,
                          "__ball rpos err (%+.3f %+.3f) %.3f",
                          tmpv.x, tmpv.y, tmpv.r() );
            dlog.addText( Logger::WORLD,
                          "____internal (%+.3f %+.3f) %.3f",
                          world.ball().rposError().x,
                          world.ball().rposError().y,
                          world.ball().rposError().r() );
            break;
        }
    }
}
/*!

*/
void
DebugClient::toStr( const WorldModel & world,
                    const ActionEffector & effector )
{
    std::ostringstream ostr;

    ostr << "((debug (format-version 3)) (time "
         << world.time().cycle() << ")";


    // self
    /*
      SELF ::=  (s SIDE PLAYER_NUMBER POS_X POS_Y VEL_X VEL_Y
      BODY_DIRECTION FACE_DIRECTION  [(c "COMMENT")])
      where SIDE is 'l' or 'r'.
      where PLAYER_NUMBER is 1 to 11.
      where POS_X and POS_Y is absolute coordinate.
      where VEL_X and VEL_Y is absolute velocity.
      where BODY_DIRECTION is absolute player body direction (degree).
      where NECK_DIRECTION is body relative face direction (degree).
      This is equals to (absolute_face_direction - BODY_DIRECTION).
      where COMMENT is a string.
      Typically, it is used as information accuracy.
    */
    if ( world.self().posValid() )
    {
        ostr << " (s "
             << ( world.ourSide() == LEFT ? "l " : "r " )
             << world.self().unum() << ' '
             << ROUND(world.self().pos().x, 0.01) << ' '
             << ROUND(world.self().pos().y, 0.01) << ' '
             << ROUND(world.self().vel().x, 0.01) << ' '
             << ROUND(world.self().vel().y, 0.01) << ' '
             << ROUND(world.self().body().degree(), 0.1) << ' '
             << ROUND(world.self().neck().degree(), 0.1) << " (c \""
             << world.self().posCount() << ' '
            //<< '(' << ROUND(world.self().posError().x, 0.001)
            //<< ", " << ROUND(world.self().posError().y, 0.001) << ") "
             << world.self().velCount() << ' '
             << world.self().faceCount();
        if ( world.self().card() == YELLOW ) ostr << "y";
        ostr << "\"))";
    }

    // ball
    /*
      BALL_INFO ::=  (b POS_X POS_Y [VEL_X VEL_Y] [(c "COMMENT")])
    */
    if ( world.ball().posValid() )
    {
        ostr << " (b "
             << ROUND(world.ball().pos().x, 0.01) << ' '
             << ROUND(world.ball().pos().y, 0.01);
        if ( world.ball().velValid() )
        {
            ostr << ' ' << ROUND(world.ball().vel().x, 0.01)
                 << ' ' << ROUND(world.ball().vel().y, 0.01);
        }
        ostr << " (c \"g" << world.ball().posCount()
             << 'r' << world.ball().rposCount()
            //<< "(" << ROUND(world.ball().rpos().x, 0.01)
            // << ", " << ROUND(world.ball().rpos().y, 0.01) << ')'
             << 'v' << world.ball().velCount()
            //<< "(" << ROUND(world.ball().vel().x, 0.01)
            // << ", " << ROUND(world.ball().vel().y, 0.01) << ')'
             << "\"))";
    }

    // players
    /*
      PLAYER_INFO ::=  (TEAM [PLAYER_NUMBER] POS_X POS_Y
      [(bd BODY_DIRECTION)] [(c "COMMENT")])
      TEAM is one of follows.
      't' (teammate), 'o' (opponent),
      'u' (unknown), 'ut' (unknown teammate), 'ut' (unknown opponent).
      When TEAM is 't' or 'o', PLAYER_NUMBER must be specified.
      Otherwise PLAYER_NUMBER must not be specified.
      Body direction and comment is optional.
    */

    std::for_each( world.teammates().begin(),
                   world.teammates().end(),
                   PlayerPrinter( ostr, 't' ) );

    std::for_each( world.opponents().begin(),
                   world.opponents().end(),
                   PlayerPrinter( ostr, 'o' ) );

    std::for_each( world.unknownPlayers().begin(),
                   world.unknownPlayers().end(),
                   PlayerPrinter( ostr, 'u' ) );

    // say message
    if ( ! effector.getSayMessage().empty() )
    {
        ostr << " (say \"";
        for ( std::vector< const SayMessage * >::const_iterator it = effector.sayMessageCont().begin();
              it != effector.sayMessageCont().end();
              ++it )
        {
            (*it)->printDebug( ostr );
        }
        ostr << " {" << effector.getSayMessage() << "}\")";
    }

    // heard information
    if ( world.audioMemory().time() == world.time() )
    {
        ostr << " (hear ";
        world.audioMemory().printDebug( ostr );
        ostr << ')';
    }

    // target number
    if ( M_target_unum != Unum_Unknown )
    {
        ostr << " (target-teammate " << M_target_unum << ")";
    }

    // target point
    if ( M_target_point.isValid() )
    {
        ostr << " (target-point "
             << M_target_point.x << " " << M_target_point.y
             << ")";
    }

    // message
    if ( ! M_message.empty() )
    {
        ostr << " (message \"" << M_message << "\")";
    }

    // lines
    std::for_each( M_lines.begin(), M_lines.end(),
                   LinePrinter( ostr ) );
    // triangles
    std::for_each( M_triangles.begin(), M_triangles.end(),
                   TrianglePrinter( ostr ) );
    // rectangles
    std::for_each( M_rectangles.begin(), M_rectangles.end(),
                   RectPrinter( ostr ) );
    // circles
    std::for_each( M_circles.begin(), M_circles.end(),
                   CirclePrinter( ostr ) );

    ostr << ")";

    M_main_buffer.assign( ostr.str() );
}
Exemple #9
0
/*!

 */
void
CrossGenerator::updatePasser( const WorldModel & wm )
{
    if ( wm.self().isKickable()
         && ! wm.self().isFrozen() )
    {
        M_passer = &wm.self();
        M_first_point = wm.ball().pos();
#ifdef DEBUG_UPDATE_PASSER
        dlog.addText( Logger::CROSS,
                      __FILE__" (updatePasser) self kickable." );
#endif
        return;
    }

    int s_min = wm.interceptTable()->selfReachCycle();
    int t_min = wm.interceptTable()->teammateReachCycle();
    int o_min = wm.interceptTable()->opponentReachCycle();

    int our_min = std::min( s_min, t_min );
    if ( o_min < std::min( our_min - 4, (int)rint( our_min * 0.9 ) ) )
    {
#ifdef DEBUG_UPDATE_PASSER
        dlog.addText( Logger::CROSS,
                      __FILE__" (updatePasser) opponent ball." );
#endif
        return;
    }

    if ( s_min <= t_min )
    {
        if ( s_min <= 2 )
        {
            M_passer = &wm.self();
            M_first_point = wm.ball().inertiaPoint( s_min );
        }
    }
    else
    {
        if ( t_min <= 2 )
        {
            M_passer = wm.interceptTable()->fastestTeammate();
            M_first_point = wm.ball().inertiaPoint( t_min );
        }
    }

    if ( ! M_passer )
    {
#ifdef DEBUG_UPDATE_PASSER
        dlog.addText( Logger::CROSS,
                      __FILE__" (updatePasser) no passer." );
#endif
        return;
    }

    if ( M_passer->unum() != wm.self().unum() )
    {
        if ( M_first_point.dist2( wm.self().pos() ) > std::pow( 20.0, 2 ) )
        {
            M_passer = static_cast< const AbstractPlayerObject * >( 0 );
#ifdef DEBUG_UPDATE_PASSER
            dlog.addText( Logger::CROSS,
                          __FILE__" (updatePasser) passer is too far." );
#endif
            return;
        }
    }

#ifdef DEBUG_UPDATE_PASSER
    dlog.addText( Logger::CROSS,
                  __FILE__" (updatePasser) passer=%d(%.1f %.1f) reachStep=%d startPos=(%.1f %.1f)",
                  M_passer->unum(),
                  M_passer->pos().x, M_passer->pos().y,
                  t_min,
                  M_first_point.x, M_first_point.y );
#endif
}
/*!

 */
double
TackleGenerator::evaluate( const WorldModel & wm,
                           const TackleResult & result )
{
    const ServerParam & SP = ServerParam::i();

    const Vector2D ball_end_point = inertia_final_point( wm.ball().pos(),
                                                         result.ball_vel_,
                                                         SP.ballDecay() );
    const Segment2D ball_line( wm.ball().pos(), ball_end_point );
    const double ball_speed = result.ball_speed_;
    const AngleDeg ball_move_angle = result.ball_move_angle_;

#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "(evaluate) angle=%.1f speed=%.2f move_angle=%.1f end_point=(%.2f %.2f)",
                  result.tackle_angle_.degree(),
                  ball_speed,
                  ball_move_angle.degree(),
                  ball_end_point.x, ball_end_point.y );
#endif

    //
    // moving to their goal
    //
    if ( ball_end_point.x > SP.pitchHalfLength()
         && wm.ball().pos().dist2( SP.theirTeamGoalPos() ) < std::pow( 20.0, 2 ) )
    {
        const Line2D goal_line( Vector2D( SP.pitchHalfLength(), 10.0 ),
                                Vector2D( SP.pitchHalfLength(), -10.0 ) );
        const Vector2D intersect = ball_line.intersection( goal_line );
        if ( intersect.isValid()
             && intersect.absY() < SP.goalHalfWidth() )
        {
            double shoot_score = 1000000.0;
            double speed_rate = 1.0 - std::exp( - std::pow( ball_speed, 2 )
                                                / ( 2.0 * std::pow( SP.ballSpeedMax()*0.5, 2 ) ) );
            double y_rate = std::exp( - std::pow( intersect.absY(), 2 )
                                      / ( 2.0 * std::pow( SP.goalWidth(), 2 ) ) );
            shoot_score *= speed_rate;
            shoot_score *= y_rate;
#ifdef DEBUG_PRINT
            dlog.addText( Logger::CLEAR,
                          "__ shoot %f (speed_rate=%f y_rate=%f)",
                          shoot_score, speed_rate, y_rate );
#endif
            return shoot_score;
        }
    }

    //
    // moving to our goal
    //
    if ( ball_end_point.x < -SP.pitchHalfLength() )
    {
        const Line2D goal_line( Vector2D( -SP.pitchHalfLength(), 10.0 ),
                                Vector2D( -SP.pitchHalfLength(), -10.0 ) );
        const Vector2D intersect = ball_line.intersection( goal_line );
        if ( intersect.isValid()
             && intersect.absY() < SP.goalHalfWidth() + 1.0 )
        {
            double shoot_score = 0.0;
            double y_penalty = ( -10000.0
                                 * std::exp( - std::pow( intersect.absY() - SP.goalHalfWidth(), 2 )
                                             / ( 2.0 * std::pow( SP.goalHalfWidth(), 2 ) ) ) );
            double speed_bonus = ( +10000.0
                                   * std::exp( - std::pow( ball_speed, 2 )
                                               / ( 2.0 * std::pow( SP.ballSpeedMax()*0.5, 2 ) ) ) );
            shoot_score = y_penalty + speed_bonus;
#ifdef DEBUG_PRINT
            dlog.addText( Logger::CLEAR,
                          "__ in our goal %f (y_pealty=%f speed_bonus=%f)",
                          shoot_score, y_penalty, speed_bonus );
#endif
            return shoot_score;
        }
    }

    //
    // normal evaluation
    //

    int opponent_reach_step = predictOpponentsReachStep( wm,
                                                         wm.ball().pos(),
                                                         result.ball_vel_,
                                                         ball_move_angle );
    Vector2D final_point = inertia_n_step_point( wm.ball().pos(),
                                                 result.ball_vel_,
                                                 opponent_reach_step,
                                                 SP.ballDecay() );
    {
        Segment2D final_segment( wm.ball().pos(), final_point );
        Rect2D pitch = Rect2D::from_center( 0.0, 0.0, SP.pitchLength(), SP.pitchWidth() );
        Vector2D intersection;
        int n = pitch.intersection( final_segment, &intersection, NULL );
        if ( n > 0 )
        {
            final_point = intersection;
        }
    }

#if 1

    AngleDeg our_goal_angle = ( SP.ourTeamGoalPos() - wm.ball().pos() ).th();
    double our_goal_angle_diff = ( our_goal_angle - ball_move_angle ).abs();
    double our_goal_angle_rate = 1.0 - std::exp( - std::pow( our_goal_angle_diff, 2 )
                                                 / ( 2.0 * std::pow( 40.0, 2 ) ) );

    double y_rate = ( final_point.absY() > SP.pitchHalfWidth() - 0.1
                      ? 1.0
                      : std::exp( - std::pow( final_point.absY() - SP.pitchHalfWidth(), 2 )
                                  / ( 2.0 * std::pow( SP.pitchHalfWidth() * 0.7, 2 ) ) ) );
    double opp_rate = 1.0 - std::exp( - std::pow( (double)opponent_reach_step, 2 )
                                      / ( 2.0 * std::pow( 30.0, 2 ) ) );

    double score = 10000.0 * our_goal_angle_rate * y_rate * opp_rate;

#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "__ goal_angle_rate=%f",
                  our_goal_angle_rate, y_rate, score );
    dlog.addText( Logger::CLEAR,
                  "__ y_rate=%f",
                  our_goal_angle_rate, y_rate, score );
    dlog.addText( Logger::CLEAR,
                  "__ opp_rate=%f",
                  opp_rate );

    dlog.addText( Logger::CLEAR,
                  ">>> score=%f",
                  score );
#endif

    return score;

#else

    double x_val = ( final_point.x > SP.pitchHalfLength()
                     ? 1.0
                     : std::exp( - std::pow( final_point.x - SP.pitchHalfLength(), 2 )
                                 / ( 2.0 * std::pow( SP.pitchLength() * 0.4, 2 ) ) ) );
    double y_val = ( final_point.absY() > SP.pitchHalfWidth()
                     ? 1.0
                     : std::exp( - std::pow( final_point.absY() - SP.pitchHalfWidth(), 2 )
                                 / ( 2.0 * std::pow( SP.pitchHalfWidth() * 0.7, 2 ) ) ) );


    double opp_goal_dist = SP.theirTeamGoalPos().dist( final_point );
    double opp_goal_dist_val = std::exp( - std::pow( opp_goal_dist, 2 )
                                         / ( 2.0 * std::pow( 20.0, 2 ) ) );

    double our_goal_dist = SP.ourTeamGoalPos().dist( final_point );
    double our_goal_dist_rate = 1.0 - std::exp( - std::pow( our_goal_dist, 2 )
                                                / ( 2.0 * std::pow( 20.0, 2 ) ) );


    double opp_rate = 1.0 - std::exp( - std::pow( (double)opponent_reach_step, 2 )
                                      / ( 2.0 * std::pow( 30.0, 2 ) ) );

    double score = 0.0;

    score += 1000.0 * x_val;
#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "__ x_val %f (%f)", 10000.0 * x_val, score );
#endif

    score += 1000.0 * y_val;
#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "__ y_val %f (%f)", 1000.0 * y_val, score );
#endif

    score += 1000.0 * opp_goal_dist_val;
#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "__ opp_goal_dist_val %f (%f)", 1000.0 * opp_goal_dist_val, score );
#endif

    score *= our_goal_dist_rate;
#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "__ our_goal_dist=%.2f rate=%f (%f)",
                  our_goal_dist, our_goal_dist_rate, score );
#endif

    score *= opp_rate;
#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  "__ opponent_reach_step=%d rate=%f (%f)",
                  opponent_reach_step, opp_rate, score );
#endif

    return score;

#endif
}
/*!

 */
void
TackleGenerator::calculate( const WorldModel & wm )
{
    const ServerParam & SP = ServerParam::i();

    const double min_angle = SP.minMoment();
    const double max_angle = SP.maxMoment();
    const double angle_step = std::fabs( max_angle - min_angle ) / ANGLE_DIVS;

#ifdef ASSUME_OPPONENT_KICK
    const Vector2D goal_pos = SP.ourTeamGoalPos();
    const bool shootable_area = ( wm.ball().pos().dist2( goal_pos ) < std::pow( 18.0, 2 ) );
    const Vector2D shoot_accel = ( goal_pos - wm.ball().pos() ).setLengthVector( 2.0 );
#endif

    const AngleDeg ball_rel_angle = wm.ball().angleFromSelf() - wm.self().body();
    const double tackle_rate
        = SP.tacklePowerRate()
        * ( 1.0 - 0.5 * ball_rel_angle.abs() / 180.0 );

#ifdef DEBUG_PRINT
    dlog.addText( Logger::CLEAR,
                  __FILE__": min_angle=%.1f max_angle=%.1f angle_step=%.1f",
                  min_angle, max_angle, angle_step );
    dlog.addText( Logger::CLEAR,
                  __FILE__": ball_rel_angle=%.1f tackle_rate=%.1f",
                  ball_rel_angle.degree(), tackle_rate );
#endif

    for ( int a = 0; a < ANGLE_DIVS; ++a )
    {
        const AngleDeg dir = min_angle + angle_step * a;

        double eff_power= ( SP.maxBackTacklePower()
                            + ( SP.maxTacklePower() - SP.maxBackTacklePower() )
                            * ( 1.0 - ( dir.abs() / 180.0 ) ) );
        eff_power *= tackle_rate;

        AngleDeg angle = wm.self().body() + dir;
        Vector2D accel = Vector2D::from_polar( eff_power, angle );

#ifdef ASSUME_OPPONENT_KICK
        if ( shootable_area
             && wm.existKickableOpponent() )
        {
            accel += shoot_accel;
            double d = accel.r();
            if ( d > SP.ballAccelMax() )
            {
                accel *= ( SP.ballAccelMax() / d );
            }
        }
#endif

        Vector2D vel = wm.ball().vel() + accel;

        double speed = vel.r();
        if ( speed > SP.ballSpeedMax() )
        {
            vel *= ( SP.ballSpeedMax() / speed );
        }

        M_candidates.push_back( TackleResult( angle, vel ) );
#ifdef DEBUG_PRINT
        const TackleResult & result = M_candidates.back();
        dlog.addText( Logger::CLEAR,
                      "%d: angle=%.1f(dir=%.1f), result: vel(%.2f %.2f ) speed=%.2f move_angle=%.1f",
                      a,
                      result.tackle_angle_.degree(), dir.degree(),
                      result.ball_vel_.x, result.ball_vel_.y,
                      result.ball_speed_, result.ball_move_angle_.degree() );
#endif
    }


    M_best_result.clear();

    const Container::iterator end = M_candidates.end();
    for ( Container::iterator it = M_candidates.begin();
          it != end;
          ++it )
    {
        it->score_ = evaluate( wm, *it );

#ifdef DEBUG_PRINT
        Vector2D ball_end_point = inertia_final_point( wm.ball().pos(),
                                                       it->ball_vel_,
                                                       SP.ballDecay() );
        dlog.addLine( Logger::CLEAR,
                      wm.ball().pos(),
                      ball_end_point,
                      "#0000ff" );
        char buf[16];
        snprintf( buf, 16, "%.3f", it->score_ );
        dlog.addMessage( Logger::CLEAR,
                         ball_end_point, buf, "#ffffff" );
#endif

        if ( it->score_ > M_best_result.score_ )
        {
#ifdef DEBUG_PRINT
            dlog.addText( Logger::CLEAR,
                          ">>>> updated" );
#endif
            M_best_result = *it;
        }
    }


#ifdef DEBUG_PRINT
    dlog.addLine( Logger::CLEAR,
                  wm.ball().pos(),
                  inertia_final_point( wm.ball().pos(),
                                       M_best_result.ball_vel_,
                                       SP.ballDecay() ),
                  "#ff0000" );
    dlog.addText( Logger::CLEAR,
                  "==== best_angle=%.1f score=%f speed=%.3f move_angle=%.1f",
                  M_best_result.tackle_angle_.degree(),
                  M_best_result.score_,
                  M_best_result.ball_speed_,
                  M_best_result.ball_move_angle_.degree() );
#endif
}
/*!

 */
Formation::Ptr
Strategy::getFormation( const WorldModel & wm ) const
{
    //
    // play on
    //
    if ( wm.gameMode().type() == GameMode::PlayOn )
    {
        switch ( M_current_situation ) {
        case Defense_Situation:
            return M_defense_formation;
        case Offense_Situation:
            return M_offense_formation;
        default:
            break;
        }
        return M_normal_formation;
    }

    //
    // kick in, corner kick
    //
    if ( wm.gameMode().type() == GameMode::KickIn_
         || wm.gameMode().type() == GameMode::CornerKick_ )
    {
        if ( wm.ourSide() == wm.gameMode().side() )
        {
            // our kick-in or corner-kick
            return M_kickin_our_formation;
        }
        else
        {
            return M_setplay_opp_formation;
        }
    }

    //
    // our indirect free kick
    //
    if ( ( wm.gameMode().type() == GameMode::BackPass_
           && wm.gameMode().side() == wm.theirSide() )
         || ( wm.gameMode().type() == GameMode::IndFreeKick_
              && wm.gameMode().side() == wm.ourSide() ) )
    {
        return M_indirect_freekick_our_formation;
    }

    //
    // opponent indirect free kick
    //
    if ( ( wm.gameMode().type() == GameMode::BackPass_
           && wm.gameMode().side() == wm.ourSide() )
         || ( wm.gameMode().type() == GameMode::IndFreeKick_
              && wm.gameMode().side() == wm.theirSide() ) )
    {
        return M_indirect_freekick_opp_formation;
    }

    //
    // after foul
    //
    if ( wm.gameMode().type() == GameMode::FoulCharge_
         || wm.gameMode().type() == GameMode::FoulPush_ )
    {
        if ( wm.gameMode().side() == wm.ourSide() )
        {
            //
            // opponent (indirect) free kick
            //
            if ( wm.ball().pos().x < ServerParam::i().ourPenaltyAreaLineX() + 1.0
                 && wm.ball().pos().absY() < ServerParam::i().penaltyAreaHalfWidth() + 1.0 )
            {
                return M_indirect_freekick_opp_formation;
            }
            else
            {
                return M_setplay_opp_formation;
            }
        }
        else
        {
            //
            // our (indirect) free kick
            //
            if ( wm.ball().pos().x > ServerParam::i().theirPenaltyAreaLineX()
                 && wm.ball().pos().absY() < ServerParam::i().penaltyAreaHalfWidth() )
            {
                return M_indirect_freekick_our_formation;
            }
            else
            {
                return M_setplay_our_formation;
            }
        }
    }

    //
    // goal kick
    //
    if ( wm.gameMode().type() == GameMode::GoalKick_ )
    {
        if ( wm.gameMode().side() == wm.ourSide() )
        {
            return M_goal_kick_our_formation;
        }
        else
        {
            return M_goal_kick_opp_formation;
        }
    }

    //
    // goalie catch
    //
    if ( wm.gameMode().type() == GameMode::GoalieCatch_ )
    {
        if ( wm.gameMode().side() == wm.ourSide() )
        {
            return M_goalie_catch_our_formation;
        }
        else
        {
            return M_goalie_catch_opp_formation;
        }
    }

    //
    // before kick off
    //
    if ( wm.gameMode().type() == GameMode::BeforeKickOff
         || wm.gameMode().type() == GameMode::AfterGoal_ )
    {
        return M_before_kick_off_formation;
    }

    //
    // other set play
    //
    if ( wm.gameMode().isOurSetPlay( wm.ourSide() ) )
    {
        return M_setplay_our_formation;
    }

    if ( wm.gameMode().type() != GameMode::PlayOn )
    {
        return M_setplay_opp_formation;
    }

    //
    // unknown
    //
    switch ( M_current_situation ) {
    case Defense_Situation:
        return M_defense_formation;
    case Offense_Situation:
        return M_offense_formation;
    default:
        break;
    }

    return M_normal_formation;
}
/*!

 */
void
Strategy::updatePosition( const WorldModel & wm )
{
    static GameTime s_update_time( 0, 0 );
    if ( s_update_time == wm.time() )
    {
        return;
    }
    s_update_time = wm.time();

    Formation::Ptr f = getFormation( wm );
    if ( ! f )
    {
        std::cerr << wm.teamName() << ':' << wm.self().unum() << ": "
                  << wm.time()
                  << " ***ERROR*** could not get the current formation" << std::endl;
        return;
    }

    int ball_step = 0;
    if ( wm.gameMode().type() == GameMode::PlayOn
         || wm.gameMode().type() == GameMode::GoalKick_ )
    {
        ball_step = std::min( 1000, wm.interceptTable()->teammateReachCycle() );
        ball_step = std::min( ball_step, wm.interceptTable()->opponentReachCycle() );
        ball_step = std::min( ball_step, wm.interceptTable()->selfReachCycle() );
    }

    Vector2D ball_pos = wm.ball().inertiaPoint( ball_step );

    dlog.addText( Logger::TEAM,
                  __FILE__": HOME POSITION: ball pos=(%.1f %.1f) step=%d",
                  ball_pos.x, ball_pos.y,
                  ball_step );

    M_positions.clear();
    f->getPositions( ball_pos, M_positions );

    if ( ServerParam::i().useOffside() )
    {
        double max_x = wm.offsideLineX();
        if ( ServerParam::i().kickoffOffside()
             && ( wm.gameMode().type() == GameMode::BeforeKickOff
                  || wm.gameMode().type() == GameMode::AfterGoal_ ) )
        {
            max_x = 0.0;
        }
        else
        {
            int mate_step = wm.interceptTable()->teammateReachCycle();
            if ( mate_step < 50 )
            {
                Vector2D trap_pos = wm.ball().inertiaPoint( mate_step );
                if ( trap_pos.x > max_x ) max_x = trap_pos.x;
            }

            max_x -= 1.0;
        }

        for ( int unum = 1; unum <= 11; ++unum )
        {
            if ( M_positions[unum-1].x > max_x )
            {
                dlog.addText( Logger::TEAM,
                              "____ %d offside. home_pos_x %.2f -> %.2f",
                              unum,
                              M_positions[unum-1].x, max_x );
                M_positions[unum-1].x = max_x;
            }
        }
    }

    M_position_types.clear();
    for ( int unum = 1; unum <= 11; ++unum )
    {
        PositionType type = Position_Center;
        if ( f->isSideType( unum ) )
        {
            type = Position_Left;
        }
        else if ( f->isSymmetryType( unum ) )
        {
            type = Position_Right;
        }

        M_position_types.push_back( type );

        dlog.addText( Logger::TEAM,
                      "__ %d home pos (%.2f %.2f) type=%d",
                      unum,
                      M_positions[unum-1].x, M_positions[unum-1].y,
                      type );
        dlog.addCircle( Logger::TEAM,
                        M_positions[unum-1], 0.5,
                        "#000000" );
    }
}
/*!

 */
double
Strategy::get_normal_dash_power( const WorldModel & wm )
{
    static bool s_recover_mode = false;

    if ( wm.self().staminaModel().capacityIsEmpty() )
    {
        return std::min( ServerParam::i().maxDashPower(),
                         wm.self().stamina() + wm.self().playerType().extraStamina() );
    }

    const int self_min = wm.interceptTable()->selfReachCycle();
    const int mate_min = wm.interceptTable()->teammateReachCycle();
    const int opp_min = wm.interceptTable()->opponentReachCycle();

    // check recover
    if ( wm.self().staminaModel().capacityIsEmpty() )
    {
        s_recover_mode = false;
    }
    else if ( wm.self().stamina() < ServerParam::i().staminaMax() * 0.5 )
    {
        s_recover_mode = true;
    }
    else if ( wm.self().stamina() > ServerParam::i().staminaMax() * 0.7 )
    {
        s_recover_mode = false;
    }

    /*--------------------------------------------------------*/
    double dash_power = ServerParam::i().maxDashPower();
    const double my_inc
        = wm.self().playerType().staminaIncMax()
        * wm.self().recovery();

    if ( wm.ourDefenseLineX() > wm.self().pos().x
         && wm.ball().pos().x < wm.ourDefenseLineX() + 20.0 )
    {
        dlog.addText( Logger::TEAM,
                      __FILE__": (get_normal_dash_power) correct DF line. keep max power" );
        // keep max power
        dash_power = ServerParam::i().maxDashPower();
    }
    else if ( s_recover_mode )
    {
        dash_power = my_inc - 25.0; // preffered recover value
        if ( dash_power < 0.0 ) dash_power = 0.0;

        dlog.addText( Logger::TEAM,
                      __FILE__": (get_normal_dash_power) recovering" );
    }
    // exist kickable teammate
    else if ( wm.existKickableTeammate()
              && wm.ball().distFromSelf() < 20.0 )
    {
        dash_power = std::min( my_inc * 1.1,
                               ServerParam::i().maxDashPower() );
        dlog.addText( Logger::TEAM,
                      __FILE__": (get_normal_dash_power) exist kickable teammate. dash_power=%.1f",
                      dash_power );
    }
    // in offside area
    else if ( wm.self().pos().x > wm.offsideLineX() )
    {
        dash_power = ServerParam::i().maxDashPower();
        dlog.addText( Logger::TEAM,
                      __FILE__": in offside area. dash_power=%.1f",
                      dash_power );
    }
    else if ( wm.ball().pos().x > 25.0
              && wm.ball().pos().x > wm.self().pos().x + 10.0
              && self_min < opp_min - 6
              && mate_min < opp_min - 6 )
    {
        dash_power = bound( ServerParam::i().maxDashPower() * 0.1,
                            my_inc * 0.5,
                            ServerParam::i().maxDashPower() );
        dlog.addText( Logger::TEAM,
                      __FILE__": (get_normal_dash_power) opponent ball dash_power=%.1f",
                      dash_power );
    }
    // normal
    else
    {
        dash_power = std::min( my_inc * 1.7,
                               ServerParam::i().maxDashPower() );
        dlog.addText( Logger::TEAM,
                      __FILE__": (get_normal_dash_power) normal mode dash_power=%.1f",
                      dash_power );
    }

    return dash_power;
}