🧠 IA e Aprendizado
Objetivo do Módulo
Dominar técnicas de IA para robótica humanoide: Reinforcement Learning (RL) para controle robusto, Large Language Models (LLMs) para reasoning e planejamento de alto nível, e Imitation Learning para aprender de demonstrações humanas. Essas são as fronteiras da pesquisa em humanoides.
Duração estimada: 55 minutos Pré-requisitos: Módulos 1-7 (Python, ROS2, Manipulação)
🎮 Reinforcement Learning para Controle
Conceitos Fundamentais
Agente (Robô) interage com Ambiente:
┌─────────────────────────────────────────┐
│ AMBIENTE (Mundo Real) │
│ Estado: s_t = [posição, velocidade, │
│ força, visão, ...] │
└──────────┬──────────────────────▲───────┘
│ Estado s_t │ Ação a_t
│ │
▼ │
┌──────────────────────────────────┴───────┐
│ AGENTE (Política π) │
│ Input: s_t │
│ Neural Network: [Dense → ReLU → ...] │
│ Output: a_t = π(s_t) │
└──────────┬───────────────────────────────┘
│ Recompensa r_t
▼
Objetivo: Maximizar Σ r_t
Equação de Bellman:
Q(s, a) = r + γ * max_a' Q(s', a')
Onde:
- Q(s, a): Valor de tomar ação 'a' no estado 's'
- r: Recompensa imediata
- γ: Fator de desconto (0.99 típico)
- s': Próximo estado
🏋️ Treinando Política com Stable-Baselines3
Setup
# Instalar bibliotecas de RL
pip install stable-baselines3[extra]
pip install gymnasium
pip install pybullet # Simulador de física
Ambiente Customizado: Humanoid Walk
import gymnasium as gym
from gymnasium import spaces
import numpy as np
import pybullet as p
import pybullet_data
class HumanoidWalkEnv(gym.Env):
"""
Ambiente de treinamento: humanoide aprendendo a andar.
Observações: 44 dimensões (posições e velocidades de juntas)
Ações: 17 dimensões (torques para cada junta)
Recompensa: Distância percorrida - custo de energia
"""
def __init__(self, render=False):
super().__init__()
# Conectar ao PyBullet
if render:
p.connect(p.GUI)
else:
p.connect(p.DIRECT)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.setGravity(0, 0, -9.81)
# Definir espaços de observação e ação
# 44 observações: 17 juntas × (posição + velocidade) + orientação (4)
self.observation_space = spaces.Box(
low=-np.inf,
high=np.inf,
shape=(44,),
dtype=np.float32
)
# 17 ações: torques para cada junta (-1 a 1, normalizado)
self.action_space = spaces.Box(
low=-1.0,
high=1.0,
shape=(17,),
dtype=np.float32
)
# Estado
self.robot_id = None
self.initial_position = [0, 0, 1.0] # 1 metro de altura
def reset(self, seed=None, options=None):
"""Resetar ambiente para novo episódio."""
super().reset(seed=seed)
p.resetSimulation()
p.setGravity(0, 0, -9.81)
# Carregar chão e robô
p.loadURDF("plane.urdf")
self.robot_id = p.loadURDF(
"humanoid/humanoid.urdf",
self.initial_position,
useFixedBase=False
)
# Estado inicial
observation = self._get_observation()
info = {}
return observation, info
def step(self, action):
"""
Executar ação e retornar próximo estado.
Args:
action: array de torques (17 dimensões)
Returns:
observation, reward, terminated, truncated, info
"""
# ====================================
# APLICAR AÇÕES (Torques nas juntas)
# ====================================
max_torque = 100.0 # Newtons-metro
for joint_idx in range(17):
p.setJointMotorControl2(
self.robot_id,
joint_idx,
p.TORQUE_CONTROL,
force=action[joint_idx] * max_torque
)
# Simular física
p.stepSimulation()
# ====================================
# OBTER NOVO ESTADO
# ====================================
observation = self._get_observation()
# ====================================
# CALCULAR RECOMPENSA
# ====================================
reward = self._compute_reward(action)
# ====================================
# VERIFICAR TÉRMINO
# ====================================
terminated = self._is_terminated()
truncated = False # Episódio muito longo
info = {}
return observation, reward, terminated, truncated, info
def _get_observation(self):
"""
Construir vetor de observação (44 dimensões).
"""
obs = []
# Posição e orientação do torso
pos, orn = p.getBasePositionAndOrientation(self.robot_id)
obs.extend(orn) # Quaternion (4 valores)
# Posição e velocidade de cada junta
for joint_idx in range(17):
joint_state = p.getJointState(self.robot_id, joint_idx)
obs.append(joint_state[0]) # Posição angular
obs.append(joint_state[1]) # Velocidade angular
return np.array(obs, dtype=np.float32)
def _compute_reward(self, action):
"""
Função de recompensa para incentivar caminhada.
Componentes:
1. Velocidade para frente (+)
2. Permanecer em pé (+)
3. Custo de energia (-) (torques altos)
4. Penalidade por queda (-)
"""
pos, orn = p.getBasePositionAndOrientation(self.robot_id)
vel, ang_vel = p.getBaseVelocity(self.robot_id)
# Recompensa por velocidade para frente
forward_reward = vel[0] * 5.0 # x é forward
# Recompensa por permanecer em pé (altura > 0.8m)
height_reward = max(0, pos[2] - 0.8) * 2.0
# Penalidade por energia (torques altos)
energy_cost = -0.01 * np.sum(np.square(action))
# Penalidade por queda
if pos[2] < 0.5: # Caiu
fall_penalty = -10.0
else:
fall_penalty = 0.0
# Recompensa total
reward = forward_reward + height_reward + energy_cost + fall_penalty
return reward
def _is_terminated(self):
"""Episódio termina se robô cair."""
pos, _ = p.getBasePositionAndOrientation(self.robot_id)
return pos[2] < 0.5 # Altura < 50cm = caiu
def close(self):
p.disconnect()
Treinar Política com PPO
from stable_baselines3 import PPO
from stable_baselines3.common.vec_env import DummyVecEnv, SubprocVecEnv
from stable_baselines3.common.callbacks import CheckpointCallback
def train_humanoid_walk():
"""
Treinar humanoide para andar usando PPO.
PPO (Proximal Policy Optimization):
- State-of-the-art para robótica
- Estável (não diverge facilmente)
- Sample-efficient (aprende rápido)
"""
# ====================================
# CRIAR AMBIENTES PARALELOS
# ====================================
# 16 robôs treinando simultaneamente (acelera 16x)
def make_env():
def _init():
return HumanoidWalkEnv(render=False)
return _init
num_envs = 16
env = SubprocVecEnv([make_env() for _ in range(num_envs)])
# ====================================
# CONFIGURAR ALGORITMO PPO
# ====================================
model = PPO(
policy="MlpPolicy", # Multi-Layer Perceptron (rede neural)
env=env,
learning_rate=3e-4,
n_steps=2048, # Passos por update
batch_size=64,
n_epochs=10,
gamma=0.99, # Fator de desconto
gae_lambda=0.95, # Generalized Advantage Estimation
clip_range=0.2,
ent_coef=0.01, # Entropia (exploração)
verbose=1,
tensorboard_log="./logs/humanoid_walk/"
)
# ====================================
# CALLBACKS
# ====================================
# Salvar checkpoint a cada 100k steps
checkpoint_callback = CheckpointCallback(
save_freq=100000,
save_path="./models/humanoid_walk/",
name_prefix="ppo_humanoid"
)
# ====================================
# TREINAR
# ====================================
total_timesteps = 10_000_000 # 10 milhões de passos
print(f"Iniciando treinamento por {total_timesteps:,} timesteps...")
print("Isso pode levar várias horas dependendo do hardware.")
model.learn(
total_timesteps=total_timesteps,
callback=checkpoint_callback,
progress_bar=True
)
# Salvar modelo final
model.save("humanoid_walk_final")
print("✅ Treinamento completo!")
# ====================================
# TESTAR POLÍTICA TREINADA
# ====================================
env_test = HumanoidWalkEnv(render=True)
obs, _ = env_test.reset()
for _ in range(1000):
action, _ = model.predict(obs, deterministic=True)
obs, reward, terminated, truncated, _ = env_test.step(action)
if terminated or truncated:
obs, _ = env_test.reset()
env_test.close()
if __name__ == "__main__":
train_humanoid_walk()
Monitorar Treinamento com TensorBoard
# Visualizar progresso em tempo real
tensorboard --logdir=./logs/humanoid_walk/
# Abrir no navegador: http://localhost:6006
# Métricas importantes:
# - rollout/ep_rew_mean: Recompensa média (deve aumentar)
# - train/policy_loss: Loss da política (deve estabilizar)
# - train/value_loss: Loss do critic