Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions challenge/onsite_competition/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@ In this phase, participants’ models will be deployed on **a real robot** to ev

---

## Robot
The robot uses a wheeled chassis. The chassis and camera control code can be found in the provided SDK. The camera’s default resolution is 640×480, and the depth and color images are already aligned.

The robot is an agilex [RANGER MINI 3.0](https://www.agilex.ai/solutions/1) with RGB camera and a LiDAR sensor.

## ⚙️ Installation

First, install the `InternNav` package:
Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
14 changes: 4 additions & 10 deletions challenge/onsite_competition/onsite_competition_rules_en-US.md
Original file line number Diff line number Diff line change
Expand Up @@ -82,8 +82,7 @@ Successfully completing one instruction will add 10 points to the total score, a
| Action | Score Impact |
|:--|:--|
| Successfully reach goal | +10 points |
| Minor scrape with obstacle | –2 points (cannot go below 0 for that instruction) |
| Collision with obstacle | 0 points, navigation terminated for this instruction |
| Minor scrape more than 5 times or Collision with obstacle | 0 points, navigation terminated for this instruction |

If there is a trend of continuous collisions, the referee has the right to terminate the robot’s current action.
If the collision occurs only once at the end of a forward movement when approaching an obstacle, it may be considered a minor scrape, with the severity of the impact determined by the on-site referee.
Expand All @@ -92,14 +91,9 @@ If the collision occurs only once at the end of a forward movement when approach
The goal is defined as a 2m-radius circular area (no wall crossing). The run is considered successful if the robot stops inside this area.

**Ranking Rules (Onsite Competition)**:
- Higher total score ranks higher.
- Tie-breaker: lower total completion time ranks higher.
- The final score is the success rate, calculated as the number of successful instructions divided by the total number of instructions.

## 5.2 Final Results
Final results combine online phase and onsite phase scores using a rank-based point system:
- Points per Rank:
Points = 100 – 5 × (Rank – 1)
Final results combine online phase and onsite phase scores:
- Final Score Calculation:
Final Score = (Online Points × 40%) + (Onsite Points × 60%)

If the final score the same, onsite points break the tie.
Final Score = (Online SR × 40%) + (Onsite SR × 60%)
22 changes: 8 additions & 14 deletions challenge/onsite_competition/onsite_competition_rules_zh-CN.md
Original file line number Diff line number Diff line change
Expand Up @@ -54,30 +54,24 @@

## 5. 评分细则
### 5.1 线下赛
比赛采用加分与扣分相结合的制度。每支队伍初始分为 0 分。每条指令的多次尝试将独立计分,并仅取该指令的最高得分计入总分。
比赛采用加分制度。每支队伍初始分为 0 分。每条指令的多次尝试将独立计分,并仅取该指令的最高得分计入总分。

**加分规则**:
- 成功完成1条指令,总分增加 10 分,并记录该指令的完成时间。(成功条件:在比赛中,每条指令均对应一个目标位置。目标位置定义为半径 2 米的圆形区域(不穿墙),机器人最终停止在该范围即可判定为该条指令导航成功。)

**扣分规则**:
- 运行过程中,若机器人轻微擦碰障碍物,该条指令每次扣除 2 分,最低不低于 0 分;
- 若机器人直接撞击障碍物,本次导航将被强制终止,该条指令不计分。
- 若机器人频繁刮蹭(5次)或直接撞击障碍物,本次导航将被强制终止,该条指令不计分。

| Action | Score |
|:--|:--:|
| 抵达目标 | +10 |
| 刮蹭 | -2 |
| 连续碰撞 | 本次不计分 |
| 连续刮蹭或撞击 | 本次不计分 |

有连续撞击趋势裁判有权终止当前机器人行为,如果是单次前进行为末尾抵近障碍物,可算一次剐蹭,由现场裁判判断撞击剧烈程度。
有连续撞击趋势裁判有权终止当前机器人行为,由现场裁判判断撞击剧烈程度。

**线下排名规则**:
- 总分高者排名靠前;
- 若总分相同,则以成功完成指令所耗总时间更少的队伍排名更高。
**线下计分规则**:
- 根据得分计算出 Success Rate (SR),得分除以总分得到成功率。

### 5.2 最终成绩
最终结果由线上阶段与线下阶段成绩加权计算,采用基于排名的积分制:
- **积分计算方式**:100 - 5×(排名-1)分
- **最终成绩计算**:最终积分 = 线上积分 × 40% + 线下积分 × 60%

若最终成绩相同,则以线下积分优先。
最终结果由线上阶段与线下阶段成绩加权计算:
- **最终成绩计算**:最终积分 = 线上成功率 × 40% + 线下成功率 × 60%
41 changes: 31 additions & 10 deletions challenge/onsite_competition/sdk/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import sys

from real_world_env import RealWorldEnv
from stream import app, start_env

from internnav.agent.utils.client import AgentClient
from internnav.configs.evaluator.default_config import get_config
Expand All @@ -21,6 +22,7 @@ def parse_args():
type=str,
help='current instruction to follow',
)
parser.add_argument("--tag", type=str, help="tag for the run, saved by the tag name which is team-task-trail")
return parser.parse_args()


Expand All @@ -32,6 +34,7 @@ def load_eval_cfg(config_path, attr_name='eval_cfg'):
return getattr(config_module, attr_name)


# TODO add logging for each step, saved by the tag name which is team-task-trail
def main():
args = parse_args()
print("--- Loading config from:", args.config, "---")
Expand All @@ -43,16 +46,34 @@ def main():
agent = AgentClient(cfg.agent)

# initialize real world env
env = RealWorldEnv(args.instruction)
env = RealWorldEnv()

while True:
# print("get observation...")
# obs contains {rgb, depth, instruction}
obs = env.get_observation()
# start stream
start_env(env)
app.run(host="0.0.0.0", port=8080, threaded=True)

# print("agent step...")
# action is a integer in [0, 3], agent return [{'action': [int], 'ideal_flag': bool}] (same to internvla_n1 agent)
action = agent.step(obs)[0]['action'][0] # only take the first env's action integer
try:
while True:
# print("get observation...")
# obs contains {rgb, depth, instruction}
obs = env.get_observation()
obs["instruction"] = args.instruction

# print("env step...")
env.step(action)
# print("agent step...")
# action is a integer in [0, 3], agent return [{'action': [int], 'ideal_flag': bool}] (same to internvla_n1 agent)
try:
action = agent.step(obs)[0]['action'][0]
print(f"agent step success, action is {action}")
except Exception as e:
print(f"agent step error {e}")
continue

# print("env step...")
try:
env.step(action)
print("env step success")
except Exception as e:
print(f"env step error {e}")
continue
finally:
env.close()
60 changes: 47 additions & 13 deletions challenge/onsite_competition/sdk/real_world_env.py
Original file line number Diff line number Diff line change
@@ -1,27 +1,56 @@
import threading
import time

from cam import AlignedRealSense
from control import DiscreteRobotController

from internnav.env import Env


class RealWorldEnv(Env):
def __init__(self):
def __init__(self, fps: int = 30):
self.node = DiscreteRobotController()
self.cam = AlignedRealSense()
self.latest_obs = None
self.lock = threading.Lock()
self.stop_flag = threading.Event()
self.fps = fps

# 启动相机
self.cam.start()
# 启动采集线程
self.thread = threading.Thread(target=self._capture_loop, daemon=True)
self.thread.start()

def _capture_loop(self):
"""keep capturing frames"""
interval = 1.0 / self.fps
while not self.stop_flag.is_set():
t0 = time.time()
try:
obs = self.cam.get_observation(timeout_ms=1000)
with self.lock:
self.latest_obs = obs
except Exception as e:
print("Camera capture failed:", e)
time.sleep(0.05)
dt = time.time() - t0
if dt < interval:
time.sleep(interval - dt)

def get_observation(self):
frame = self.cam.get_observation()
return frame

def step(self, action):

'''
action (int): Discrete action to apply:
- 0: no movement (stand still)
- 1: move forward
- 2: rotate left
- 3: rotate right
'''
"""return most recent frame"""
with self.lock:
return self.latest_obs

def step(self, action: int):
"""
action:
0: stand still
1: move forward
2: turn left
3: turn right
"""
if action == 0:
self.node.stand_still()
elif action == 1:
Expand All @@ -30,3 +59,8 @@ def step(self, action):
self.node.turn_left()
elif action == 3:
self.node.turn_right()

def close(self):
self.stop_flag.set()
self.thread.join(timeout=1.0)
self.cam.stop()
38 changes: 38 additions & 0 deletions challenge/onsite_competition/sdk/stream.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
# stream_server.py
import time

import cv2
from flask import Flask, Response

app = Flask(__name__)

# 由主程序注入
_env = None


def set_env(env):
"""set env from main to stream server"""
global _env
_env = env


def _mjpeg_generator(jpeg_quality: int = 80):
boundary = b"--frame"
while True:
if _env is None:
time.sleep(0.1)
continue
obs = _env.get_observation()
if obs is None:
time.sleep(0.01)
continue
frame_bgr = obs["rgb"]
ok, jpg = cv2.imencode(".jpg", frame_bgr, [cv2.IMWRITE_JPEG_QUALITY, jpeg_quality])
if not ok:
continue
yield (boundary + b"\r\n" b"Content-Type: image/jpeg\r\n\r\n" + jpg.tobytes() + b"\r\n")


@app.route("/stream")
def stream():
return Response(_mjpeg_generator(), mimetype="multipart/x-mixed-replace; boundary=frame")
Loading