Co-authored-by: Max Tuzzolino <maxtuzz@Maxs-MacBook-Pro.local>
Co-authored-by: Claude <noreply@anthropic.com>
Co-authored-by: Max Tuzzolino <max.tuzsmith@gmail.com>
Co-authored-by: Ralph Khreish <35776126+Crunchyman-ralph@users.noreply.github.com>
This commit is contained in:
Eyal Toledano
2025-09-19 18:08:20 -04:00
committed by GitHub
parent 4e126430a0
commit fce841490a
55 changed files with 3559 additions and 693 deletions

View File

@@ -27,6 +27,11 @@ export const baseConfig: Partial<UserConfig> = {
dts: isDevelopment,
minify: isProduction,
treeshake: isProduction,
// Better debugging in development
...(isDevelopment && {
keepNames: true,
splitting: false // Disable code splitting for better stack traces
}),
// Keep all npm dependencies external (available via node_modules)
external: [/^[^@./]/, /^@(?!tm\/)/]
};

View File

@@ -0,0 +1,80 @@
/**
* Base executor class providing common functionality for all executors
*/
import type { Task } from '../types/index.js';
import type { ITaskExecutor, ExecutorType, ExecutionResult } from './types.js';
import { getLogger } from '../logger/index.js';
export abstract class BaseExecutor implements ITaskExecutor {
protected readonly logger = getLogger('BaseExecutor');
protected readonly projectRoot: string;
protected readonly config: Record<string, any>;
constructor(projectRoot: string, config: Record<string, any> = {}) {
this.projectRoot = projectRoot;
this.config = config;
}
abstract execute(task: Task): Promise<ExecutionResult>;
abstract getType(): ExecutorType;
abstract isAvailable(): Promise<boolean>;
/**
* Format task details into a readable prompt
*/
protected formatTaskPrompt(task: Task): string {
const sections: string[] = [];
sections.push(`Task ID: ${task.id}`);
sections.push(`Title: ${task.title}`);
if (task.description) {
sections.push(`\nDescription:\n${task.description}`);
}
if (task.details) {
sections.push(`\nImplementation Details:\n${task.details}`);
}
if (task.testStrategy) {
sections.push(`\nTest Strategy:\n${task.testStrategy}`);
}
if (task.dependencies && task.dependencies.length > 0) {
sections.push(`\nDependencies: ${task.dependencies.join(', ')}`);
}
if (task.subtasks && task.subtasks.length > 0) {
const subtaskList = task.subtasks
.map((st) => ` - [${st.status}] ${st.id}: ${st.title}`)
.join('\n');
sections.push(`\nSubtasks:\n${subtaskList}`);
}
sections.push(`\nStatus: ${task.status}`);
sections.push(`Priority: ${task.priority}`);
return sections.join('\n');
}
/**
* Create base execution result
*/
protected createResult(
taskId: string,
success: boolean,
output?: string,
error?: string
): ExecutionResult {
return {
success,
taskId,
executorType: this.getType(),
output,
error,
startTime: new Date().toISOString(),
endTime: new Date().toISOString()
};
}
}

View File

@@ -0,0 +1,147 @@
/**
* Claude executor implementation for Task Master
*/
import { spawn } from 'child_process';
import type { Task } from '../types/index.js';
import type {
ExecutorType,
ExecutionResult,
ClaudeExecutorConfig
} from './types.js';
import { BaseExecutor } from './base-executor.js';
export class ClaudeExecutor extends BaseExecutor {
private claudeConfig: ClaudeExecutorConfig;
private currentProcess: any = null;
constructor(projectRoot: string, config: ClaudeExecutorConfig = {}) {
super(projectRoot, config);
this.claudeConfig = {
command: config.command || 'claude',
systemPrompt:
config.systemPrompt ||
'You are a helpful AI assistant helping to complete a software development task.',
additionalFlags: config.additionalFlags || []
};
}
getType(): ExecutorType {
return 'claude';
}
async isAvailable(): Promise<boolean> {
return new Promise((resolve) => {
const checkProcess = spawn('which', [this.claudeConfig.command!], {
shell: true
});
checkProcess.on('close', (code) => {
resolve(code === 0);
});
checkProcess.on('error', () => {
resolve(false);
});
});
}
async execute(task: Task): Promise<ExecutionResult> {
const startTime = new Date().toISOString();
try {
// Check if Claude is available
const isAvailable = await this.isAvailable();
if (!isAvailable) {
return this.createResult(
task.id,
false,
undefined,
`Claude CLI not found. Please ensure 'claude' command is available in PATH.`
);
}
// Format the task into a prompt
const taskPrompt = this.formatTaskPrompt(task);
const fullPrompt = `${this.claudeConfig.systemPrompt}\n\nHere is the task to complete:\n\n${taskPrompt}`;
// Execute Claude with the task details
const result = await this.runClaude(fullPrompt, task.id);
return {
...result,
startTime,
endTime: new Date().toISOString()
};
} catch (error: any) {
this.logger.error(`Failed to execute task ${task.id}:`, error);
return this.createResult(
task.id,
false,
undefined,
error.message || 'Unknown error occurred'
);
}
}
private runClaude(prompt: string, taskId: string): Promise<ExecutionResult> {
return new Promise((resolve) => {
const args = [prompt, ...this.claudeConfig.additionalFlags!];
this.logger.info(`Executing Claude for task ${taskId}`);
this.logger.debug(
`Command: ${this.claudeConfig.command} ${args.join(' ')}`
);
this.currentProcess = spawn(this.claudeConfig.command!, args, {
cwd: this.projectRoot,
shell: false,
stdio: 'inherit' // Let Claude handle its own I/O
});
this.currentProcess.on('close', (code: number) => {
this.currentProcess = null;
if (code === 0) {
resolve(
this.createResult(
taskId,
true,
'Claude session completed successfully'
)
);
} else {
resolve(
this.createResult(
taskId,
false,
undefined,
`Claude exited with code ${code}`
)
);
}
});
this.currentProcess.on('error', (error: any) => {
this.currentProcess = null;
this.logger.error(`Claude process error:`, error);
resolve(
this.createResult(
taskId,
false,
undefined,
`Failed to spawn Claude: ${error.message}`
)
);
});
});
}
async stop(): Promise<void> {
if (this.currentProcess) {
this.logger.info('Stopping Claude process...');
this.currentProcess.kill('SIGTERM');
this.currentProcess = null;
}
}
}

View File

@@ -0,0 +1,59 @@
/**
* Factory for creating task executors
*/
import type { ITaskExecutor, ExecutorOptions, ExecutorType } from './types.js';
import { ClaudeExecutor } from './claude-executor.js';
import { getLogger } from '../logger/index.js';
export class ExecutorFactory {
private static logger = getLogger('ExecutorFactory');
/**
* Create an executor based on the provided options
*/
static create(options: ExecutorOptions): ITaskExecutor {
this.logger.debug(`Creating executor of type: ${options.type}`);
switch (options.type) {
case 'claude':
return new ClaudeExecutor(options.projectRoot, options.config);
case 'shell':
// Placeholder for shell executor
throw new Error('Shell executor not yet implemented');
case 'custom':
// Placeholder for custom executor
throw new Error('Custom executor not yet implemented');
default:
throw new Error(`Unknown executor type: ${options.type}`);
}
}
/**
* Get the default executor type based on available tools
*/
static async getDefaultExecutor(
projectRoot: string
): Promise<ExecutorType | null> {
// Check for Claude first
const claudeExecutor = new ClaudeExecutor(projectRoot);
if (await claudeExecutor.isAvailable()) {
this.logger.info('Claude CLI detected as default executor');
return 'claude';
}
// Could check for other executors here
this.logger.warn('No default executor available');
return null;
}
/**
* Get list of available executor types
*/
static getAvailableTypes(): ExecutorType[] {
return ['claude', 'shell', 'custom'];
}
}

View File

@@ -0,0 +1,105 @@
/**
* Service for managing task execution
*/
import type { Task } from '../types/index.js';
import type {
ITaskExecutor,
ExecutorOptions,
ExecutionResult,
ExecutorType
} from './types.js';
import { ExecutorFactory } from './executor-factory.js';
import { getLogger } from '../logger/index.js';
export interface ExecutorServiceOptions {
projectRoot: string;
defaultExecutor?: ExecutorType;
executorConfig?: Record<string, any>;
}
export class ExecutorService {
private logger = getLogger('ExecutorService');
private projectRoot: string;
private defaultExecutor?: ExecutorType;
private executorConfig: Record<string, any>;
private currentExecutor?: ITaskExecutor;
constructor(options: ExecutorServiceOptions) {
this.projectRoot = options.projectRoot;
this.defaultExecutor = options.defaultExecutor;
this.executorConfig = options.executorConfig || {};
}
/**
* Execute a task
*/
async executeTask(
task: Task,
executorType?: ExecutorType
): Promise<ExecutionResult> {
try {
// Determine executor type
const type =
executorType ||
this.defaultExecutor ||
(await ExecutorFactory.getDefaultExecutor(this.projectRoot));
if (!type) {
return {
success: false,
taskId: task.id,
executorType: 'claude',
error:
'No executor available. Please install Claude CLI or specify an executor type.',
startTime: new Date().toISOString()
};
}
// Create executor
const executorOptions: ExecutorOptions = {
type,
projectRoot: this.projectRoot,
config: this.executorConfig
};
this.currentExecutor = ExecutorFactory.create(executorOptions);
// Check if executor is available
const isAvailable = await this.currentExecutor.isAvailable();
if (!isAvailable) {
return {
success: false,
taskId: task.id,
executorType: type,
error: `Executor ${type} is not available or not configured properly`,
startTime: new Date().toISOString()
};
}
// Execute the task
this.logger.info(`Starting task ${task.id} with ${type} executor`);
const result = await this.currentExecutor.execute(task);
return result;
} catch (error: any) {
this.logger.error(`Failed to execute task ${task.id}:`, error);
return {
success: false,
taskId: task.id,
executorType: executorType || 'claude',
error: error.message || 'Unknown error occurred',
startTime: new Date().toISOString()
};
}
}
/**
* Stop the current task execution
*/
async stopCurrentTask(): Promise<void> {
if (this.currentExecutor && this.currentExecutor.stop) {
await this.currentExecutor.stop();
this.currentExecutor = undefined;
}
}
}

View File

@@ -0,0 +1,12 @@
/**
* Public API for the executors module
*/
export * from './types.js';
export { BaseExecutor } from './base-executor.js';
export { ClaudeExecutor } from './claude-executor.js';
export { ExecutorFactory } from './executor-factory.js';
export {
ExecutorService,
type ExecutorServiceOptions
} from './executor-service.js';

View File

@@ -0,0 +1,76 @@
/**
* Executor types and interfaces for Task Master
*/
import type { Task } from '../types/index.js';
/**
* Supported executor types
*/
export type ExecutorType = 'claude' | 'shell' | 'custom';
/**
* Options for executor creation
*/
export interface ExecutorOptions {
type: ExecutorType;
projectRoot: string;
config?: Record<string, any>;
}
/**
* Result from task execution
*/
export interface ExecutionResult {
success: boolean;
taskId: string;
executorType: ExecutorType;
output?: string;
error?: string;
startTime: string;
endTime?: string;
processId?: number;
}
/**
* Base interface for all task executors
*/
export interface ITaskExecutor {
/**
* Execute a task
*/
execute(task: Task): Promise<ExecutionResult>;
/**
* Stop a running task execution
*/
stop?(): Promise<void>;
/**
* Get executor type
*/
getType(): ExecutorType;
/**
* Check if executor is available/configured
*/
isAvailable(): Promise<boolean>;
}
/**
* Configuration for Claude executor
*/
export interface ClaudeExecutorConfig {
command?: string; // Default: 'claude'
systemPrompt?: string;
additionalFlags?: string[];
}
/**
* Configuration for Shell executor
*/
export interface ShellExecutorConfig {
shell?: string; // Default: '/bin/bash'
env?: Record<string, string>;
cwd?: string;
}

View File

@@ -8,7 +8,10 @@ export {
TaskMasterCore,
createTaskMasterCore,
type TaskMasterCoreOptions,
type ListTasksResult
type ListTasksResult,
type StartTaskOptions,
type StartTaskResult,
type ConflictCheckResult
} from './task-master-core.js';
// Re-export types
@@ -55,3 +58,6 @@ export {
// Re-export logger
export { getLogger, createLogger, setGlobalLogger } from './logger/index.js';
// Re-export executors
export * from './executors/index.js';

View File

@@ -26,7 +26,7 @@ const MAX_PROMPT_LENGTH = 100000;
const MIN_TEMPERATURE = 0;
const MAX_TEMPERATURE = 2;
const MIN_MAX_TOKENS = 1;
const MAX_MAX_TOKENS = 100000;
const MAX_MAX_TOKENS = 131072;
/**
* Configuration for BaseProvider

View File

@@ -0,0 +1,308 @@
/**
* @fileoverview TaskExecutionService for handling task execution business logic
* Extracted from CLI start command to be reusable across CLI and extension
*/
import type { Task } from '../types/index.js';
import type { TaskService } from './task-service.js';
export interface StartTaskOptions {
subtaskId?: string;
dryRun?: boolean;
updateStatus?: boolean;
force?: boolean;
silent?: boolean;
}
export interface StartTaskResult {
task: Task | null;
found: boolean;
started: boolean;
subtaskId?: string;
subtask?: any;
error?: string;
executionOutput?: string;
/** Command to execute (for CLI to run directly) */
command?: {
executable: string;
args: string[];
cwd: string;
};
}
export interface ConflictCheckResult {
canProceed: boolean;
conflictingTasks: Task[];
reason?: string;
}
/**
* TaskExecutionService handles the business logic for starting and executing tasks
*/
export class TaskExecutionService {
constructor(private taskService: TaskService) {}
/**
* Start working on a task with comprehensive business logic
*/
async startTask(
taskId: string,
options: StartTaskOptions = {}
): Promise<StartTaskResult> {
try {
// Handle subtask IDs by extracting parent task ID
const { parentId, subtaskId } = this.parseTaskId(taskId);
// Check for in-progress task conflicts
if (!options.force) {
const conflictCheck = await this.checkInProgressConflicts(taskId);
if (!conflictCheck.canProceed) {
return {
task: null,
found: false,
started: false,
error: `Conflicting tasks in progress: ${conflictCheck.conflictingTasks.map((t) => `#${t.id}: ${t.title}`).join(', ')}`
};
}
}
// Get the actual task (parent task if dealing with subtask)
const task = await this.taskService.getTask(parentId);
if (!task) {
return {
task: null,
found: false,
started: false,
error: `Task ${parentId} not found`
};
}
// Find the specific subtask if provided
let subtask = undefined;
if (subtaskId && task.subtasks) {
subtask = task.subtasks.find((st) => String(st.id) === subtaskId);
}
// Update task status to in-progress if not disabled
if (options.updateStatus && !options.dryRun) {
try {
await this.taskService.updateTaskStatus(parentId, 'in-progress');
} catch (error) {
// Log but don't fail - status update is not critical
console.warn(
`Could not update task status: ${error instanceof Error ? error.message : String(error)}`
);
}
}
// Prepare execution command instead of executing directly
let started = false;
let executionOutput = 'Task ready to execute';
let command = undefined;
if (!options.dryRun) {
// Prepare the command for execution by the CLI
command = await this.prepareExecutionCommand(task, subtask);
started = !!command; // Command prepared successfully
executionOutput = command
? `Command prepared: ${command.executable} ${command.args.join(' ')}`
: 'Failed to prepare execution command';
} else {
// For dry-run, just show that we would execute
started = true;
executionOutput = 'Dry run - task would be executed';
// Also prepare command for dry run display
command = await this.prepareExecutionCommand(task, subtask);
}
return {
task,
found: true,
started,
subtaskId,
subtask,
executionOutput,
command: command || undefined
};
} catch (error) {
return {
task: null,
found: false,
started: false,
error: error instanceof Error ? error.message : String(error)
};
}
}
/**
* Check for existing in-progress tasks and determine conflicts
*/
async checkInProgressConflicts(
targetTaskId: string
): Promise<ConflictCheckResult> {
const allTasks = await this.taskService.getTaskList();
const inProgressTasks = allTasks.tasks.filter(
(task) => task.status === 'in-progress'
);
// If the target task is already in-progress, that's fine
const targetTaskInProgress = inProgressTasks.find(
(task) => task.id === targetTaskId
);
if (targetTaskInProgress) {
return { canProceed: true, conflictingTasks: [] };
}
// Check if target is a subtask and its parent is in-progress
const isSubtask = targetTaskId.includes('.');
if (isSubtask) {
const parentTaskId = targetTaskId.split('.')[0];
const parentInProgress = inProgressTasks.find(
(task) => task.id === parentTaskId
);
if (parentInProgress) {
return { canProceed: true, conflictingTasks: [] }; // Allow subtasks when parent is in-progress
}
}
// Check if other unrelated tasks are in-progress
const conflictingTasks = inProgressTasks.filter((task) => {
if (task.id === targetTaskId) return false;
// If target is a subtask, exclude its parent from conflicts
if (isSubtask) {
const parentTaskId = targetTaskId.split('.')[0];
if (task.id === parentTaskId) return false;
}
// If the in-progress task is a subtask of our target parent, exclude it
if (task.id.toString().includes('.')) {
const taskParentId = task.id.toString().split('.')[0];
if (isSubtask && taskParentId === targetTaskId.split('.')[0]) {
return false;
}
}
return true;
});
if (conflictingTasks.length > 0) {
return {
canProceed: false,
conflictingTasks,
reason: 'Other tasks are already in progress'
};
}
return { canProceed: true, conflictingTasks: [] };
}
/**
* Get the next available task to start
*/
async getNextAvailableTask(): Promise<string | null> {
const nextTask = await this.taskService.getNextTask();
return nextTask?.id || null;
}
/**
* Parse a task ID to determine if it's a subtask and extract components
*/
private parseTaskId(taskId: string): {
parentId: string;
subtaskId?: string;
} {
if (taskId.includes('.')) {
const [parentId, subtaskId] = taskId.split('.');
return { parentId, subtaskId };
}
return { parentId: taskId };
}
/**
* Check if a task can be started (no conflicts)
*/
async canStartTask(taskId: string, force = false): Promise<boolean> {
if (force) return true;
const conflictCheck = await this.checkInProgressConflicts(taskId);
return conflictCheck.canProceed;
}
/**
* Prepare execution command for the CLI to run
*/
private async prepareExecutionCommand(
task: Task,
subtask?: any
): Promise<{ executable: string; args: string[]; cwd: string } | null> {
try {
// Format the task into a prompt
const taskPrompt = this.formatTaskPrompt(task, subtask);
// Use claude command - could be extended for other executors
const executable = 'claude';
const args = [taskPrompt];
const cwd = process.cwd(); // or could get from project root
return { executable, args, cwd };
} catch (error) {
console.warn(
`Failed to prepare execution command: ${error instanceof Error ? error.message : String(error)}`
);
return null;
}
}
/**
* Format task into a prompt suitable for execution
*/
private formatTaskPrompt(task: Task, subtask?: any): string {
const workItem = subtask || task;
const itemType = subtask ? 'Subtask' : 'Task';
const itemId = subtask ? `${task.id}.${subtask.id}` : task.id;
let prompt = `${itemType} #${itemId}: ${workItem.title}\n\n`;
if (workItem.description) {
prompt += `Description:\n${workItem.description}\n\n`;
}
if (workItem.details) {
prompt += `Implementation Details:\n${workItem.details}\n\n`;
}
if (workItem.testStrategy) {
prompt += `Test Strategy:\n${workItem.testStrategy}\n\n`;
}
if (task.dependencies && task.dependencies.length > 0) {
prompt += `Dependencies: ${task.dependencies.join(', ')}\n\n`;
}
prompt += `Please help me implement this ${itemType.toLowerCase()}.`;
return prompt;
}
/**
* Get task with subtask resolution
*/
async getTaskWithSubtask(
taskId: string
): Promise<{ task: Task | null; subtask?: any; subtaskId?: string }> {
const { parentId, subtaskId } = this.parseTaskId(taskId);
const task = await this.taskService.getTask(parentId);
if (!task) {
return { task: null };
}
if (subtaskId && task.subtasks) {
const subtask = task.subtasks.find((st) => String(st.id) === subtaskId);
return { task, subtask, subtaskId };
}
return { task };
}
}

View File

@@ -117,7 +117,7 @@ export class TaskService {
tasks,
total: rawTasks.length,
filtered: filteredEntities.length,
tag: options.tag, // Only include tag if explicitly provided
tag: tag, // Return the actual tag being used (either explicitly provided or active tag)
storageType: this.getStorageType()
};
} catch (error) {
@@ -219,43 +219,127 @@ export class TaskService {
/**
* Get next available task to work on
* Prioritizes eligible subtasks from in-progress parent tasks before falling back to top-level tasks
*/
async getNextTask(tag?: string): Promise<Task | null> {
const result = await this.getTaskList({
tag,
filter: {
status: ['pending', 'in-progress']
status: ['pending', 'in-progress', 'done']
}
});
// Find tasks with no dependencies or all dependencies satisfied
const completedIds = new Set(
result.tasks.filter((t) => t.status === 'done').map((t) => t.id)
);
const allTasks = result.tasks;
const priorityValues = { critical: 4, high: 3, medium: 2, low: 1 };
const availableTasks = result.tasks.filter((task) => {
if (task.status === 'done' || task.status === 'blocked') {
return false;
// Helper to convert subtask dependencies to full dotted notation
const toFullSubId = (
parentId: string,
maybeDotId: string | number
): string => {
if (typeof maybeDotId === 'string' && maybeDotId.includes('.')) {
return maybeDotId;
}
return `${parentId}.${maybeDotId}`;
};
if (!task.dependencies || task.dependencies.length === 0) {
return true;
// Build completed IDs set (both tasks and subtasks)
const completedIds = new Set<string>();
allTasks.forEach((t) => {
if (t.status === 'done') {
completedIds.add(String(t.id));
}
if (Array.isArray(t.subtasks)) {
t.subtasks.forEach((st) => {
if (st.status === 'done') {
completedIds.add(`${t.id}.${st.id}`);
}
});
}
return task.dependencies.every((depId) =>
completedIds.has(depId.toString())
);
});
// Sort by priority
availableTasks.sort((a, b) => {
const priorityOrder = { critical: 0, high: 1, medium: 2, low: 3 };
const aPriority = priorityOrder[a.priority || 'medium'];
const bPriority = priorityOrder[b.priority || 'medium'];
return aPriority - bPriority;
// 1) Look for eligible subtasks from in-progress parent tasks
const candidateSubtasks: Array<Task & { parentId?: string }> = [];
allTasks
.filter((t) => t.status === 'in-progress' && Array.isArray(t.subtasks))
.forEach((parent) => {
parent.subtasks!.forEach((st) => {
const stStatus = (st.status || 'pending').toLowerCase();
if (stStatus !== 'pending' && stStatus !== 'in-progress') return;
const fullDeps =
st.dependencies?.map((d) => toFullSubId(String(parent.id), d)) ??
[];
const depsSatisfied =
fullDeps.length === 0 ||
fullDeps.every((depId) => completedIds.has(String(depId)));
if (depsSatisfied) {
candidateSubtasks.push({
id: `${parent.id}.${st.id}`,
title: st.title || `Subtask ${st.id}`,
status: st.status || 'pending',
priority: st.priority || parent.priority || 'medium',
dependencies: fullDeps,
parentId: String(parent.id),
description: st.description,
details: st.details,
testStrategy: st.testStrategy,
subtasks: []
} as Task & { parentId: string });
}
});
});
if (candidateSubtasks.length > 0) {
// Sort by priority → dependency count → parent ID → subtask ID
candidateSubtasks.sort((a, b) => {
const pa =
priorityValues[a.priority as keyof typeof priorityValues] ?? 2;
const pb =
priorityValues[b.priority as keyof typeof priorityValues] ?? 2;
if (pb !== pa) return pb - pa;
if (a.dependencies!.length !== b.dependencies!.length) {
return a.dependencies!.length - b.dependencies!.length;
}
// Compare parent then subtask ID numerically
const [aPar, aSub] = String(a.id).split('.').map(Number);
const [bPar, bSub] = String(b.id).split('.').map(Number);
if (aPar !== bPar) return aPar - bPar;
return aSub - bSub;
});
return candidateSubtasks[0];
}
// 2) Fall back to top-level tasks (original logic)
const eligibleTasks = allTasks.filter((task) => {
const status = (task.status || 'pending').toLowerCase();
if (status !== 'pending' && status !== 'in-progress') return false;
const deps = task.dependencies ?? [];
return deps.every((depId) => completedIds.has(String(depId)));
});
return availableTasks[0] || null;
if (eligibleTasks.length === 0) return null;
// Sort by priority → dependency count → task ID
const nextTask = eligibleTasks.sort((a, b) => {
const pa = priorityValues[a.priority as keyof typeof priorityValues] ?? 2;
const pb = priorityValues[b.priority as keyof typeof priorityValues] ?? 2;
if (pb !== pa) return pb - pa;
const da = (a.dependencies ?? []).length;
const db = (b.dependencies ?? []).length;
if (da !== db) return da - db;
return Number(a.id) - Number(b.id);
})[0];
return nextTask;
}
/**

View File

@@ -107,7 +107,7 @@ export class FileStorage implements IStorage {
*/
async loadTask(taskId: string, tag?: string): Promise<Task | null> {
const tasks = await this.loadTasks(tag);
return tasks.find((task) => task.id === taskId) || null;
return tasks.find((task) => String(task.id) === String(taskId)) || null;
}
/**
@@ -267,7 +267,7 @@ export class FileStorage implements IStorage {
tag?: string
): Promise<void> {
const tasks = await this.loadTasks(tag);
const taskIndex = tasks.findIndex((t) => t.id === taskId.toString());
const taskIndex = tasks.findIndex((t) => String(t.id) === String(taskId));
if (taskIndex === -1) {
throw new Error(`Task ${taskId} not found`);
@@ -276,7 +276,7 @@ export class FileStorage implements IStorage {
tasks[taskIndex] = {
...tasks[taskIndex],
...updates,
id: taskId.toString()
id: String(taskId) // Keep consistent with normalizeTaskIds
};
await this.saveTasks(tasks, tag);
}
@@ -286,7 +286,7 @@ export class FileStorage implements IStorage {
*/
async deleteTask(taskId: string, tag?: string): Promise<void> {
const tasks = await this.loadTasks(tag);
const filteredTasks = tasks.filter((t) => t.id !== taskId);
const filteredTasks = tasks.filter((t) => String(t.id) !== String(taskId));
if (filteredTasks.length === tasks.length) {
throw new Error(`Task ${taskId} not found`);

View File

@@ -8,6 +8,12 @@ import {
type TaskListResult as ListTasksResult,
type GetTaskListOptions
} from './services/task-service.js';
import {
TaskExecutionService,
type StartTaskOptions,
type StartTaskResult,
type ConflictCheckResult
} from './services/task-execution-service.js';
import { ERROR_CODES, TaskMasterError } from './errors/task-master-error.js';
import type { IConfiguration } from './interfaces/configuration.interface.js';
import type {
@@ -16,6 +22,12 @@ import type {
TaskFilter,
StorageType
} from './types/index.js';
import {
ExecutorService,
type ExecutorServiceOptions,
type ExecutionResult,
type ExecutorType
} from './executors/index.js';
/**
* Options for creating TaskMasterCore instance
@@ -26,10 +38,15 @@ export interface TaskMasterCoreOptions {
}
/**
* Re-export result types from TaskService
* Re-export result types from services
*/
export type { TaskListResult as ListTasksResult } from './services/task-service.js';
export type { GetTaskListOptions } from './services/task-service.js';
export type {
StartTaskOptions,
StartTaskResult,
ConflictCheckResult
} from './services/task-execution-service.js';
/**
* TaskMasterCore facade class
@@ -38,6 +55,8 @@ export type { GetTaskListOptions } from './services/task-service.js';
export class TaskMasterCore {
private configManager: ConfigManager;
private taskService: TaskService;
private taskExecutionService: TaskExecutionService;
private executorService: ExecutorService | null = null;
/**
* Create and initialize a new TaskMasterCore instance
@@ -60,6 +79,7 @@ export class TaskMasterCore {
// Services will be initialized in the initialize() method
this.configManager = null as any;
this.taskService = null as any;
this.taskExecutionService = null as any;
}
/**
@@ -86,6 +106,9 @@ export class TaskMasterCore {
// Create task service
this.taskService = new TaskService(this.configManager);
await this.taskService.initialize();
// Create task execution service
this.taskExecutionService = new TaskExecutionService(this.taskService);
} catch (error) {
throw new TaskMasterError(
'Failed to initialize TaskMasterCore',
@@ -175,6 +198,85 @@ export class TaskMasterCore {
await this.configManager.setActiveTag(tag);
}
// ==================== Task Execution Methods ====================
/**
* Start working on a task with comprehensive business logic
*/
async startTask(
taskId: string,
options: StartTaskOptions = {}
): Promise<StartTaskResult> {
return this.taskExecutionService.startTask(taskId, options);
}
/**
* Check if a task can be started (no conflicts)
*/
async canStartTask(taskId: string, force = false): Promise<boolean> {
return this.taskExecutionService.canStartTask(taskId, force);
}
/**
* Check for existing in-progress tasks and determine conflicts
*/
async checkInProgressConflicts(
targetTaskId: string
): Promise<ConflictCheckResult> {
return this.taskExecutionService.checkInProgressConflicts(targetTaskId);
}
/**
* Get task with subtask resolution
*/
async getTaskWithSubtask(
taskId: string
): Promise<{ task: Task | null; subtask?: any; subtaskId?: string }> {
return this.taskExecutionService.getTaskWithSubtask(taskId);
}
/**
* Get the next available task to start
*/
async getNextAvailableTask(): Promise<string | null> {
return this.taskExecutionService.getNextAvailableTask();
}
// ==================== Executor Service Methods ====================
/**
* Initialize executor service (lazy initialization)
*/
private getExecutorService(): ExecutorService {
if (!this.executorService) {
const executorOptions: ExecutorServiceOptions = {
projectRoot: this.configManager.getProjectRoot()
};
this.executorService = new ExecutorService(executorOptions);
}
return this.executorService;
}
/**
* Execute a task
*/
async executeTask(
task: Task,
executorType?: ExecutorType
): Promise<ExecutionResult> {
const executor = this.getExecutorService();
return executor.executeTask(task, executorType);
}
/**
* Stop the current task execution
*/
async stopCurrentTask(): Promise<void> {
if (this.executorService) {
await this.executorService.stopCurrentTask();
}
}
/**
* Update task status
*/
@@ -195,6 +297,10 @@ export class TaskMasterCore {
* Close and cleanup resources
*/
async close(): Promise<void> {
// Stop any running executors
if (this.executorService) {
await this.executorService.stopCurrentTask();
}
// TaskService handles storage cleanup internally
}
}

View File

@@ -0,0 +1,82 @@
/**
* Tests for executor functionality
*/
import { describe, it, expect, beforeEach, vi } from 'vitest';
import {
ExecutorFactory,
ClaudeExecutor,
type ExecutorOptions
} from '../../src/executors/index.js';
describe('ExecutorFactory', () => {
const mockProjectRoot = '/test/project';
it('should create a Claude executor', () => {
const options: ExecutorOptions = {
type: 'claude',
projectRoot: mockProjectRoot
};
const executor = ExecutorFactory.create(options);
expect(executor).toBeInstanceOf(ClaudeExecutor);
});
it('should throw error for unimplemented executor types', () => {
const options: ExecutorOptions = {
type: 'shell',
projectRoot: mockProjectRoot
};
expect(() => ExecutorFactory.create(options)).toThrow(
'Shell executor not yet implemented'
);
});
it('should get available executor types', () => {
const types = ExecutorFactory.getAvailableTypes();
expect(types).toContain('claude');
expect(types).toContain('shell');
expect(types).toContain('custom');
});
});
describe('ClaudeExecutor', () => {
const mockProjectRoot = '/test/project';
let executor: ClaudeExecutor;
beforeEach(() => {
executor = new ClaudeExecutor(mockProjectRoot);
});
it('should return claude as executor type', () => {
expect(executor.getType()).toBe('claude');
});
it('should format task prompt correctly', () => {
const mockTask = {
id: '1',
title: 'Test Task',
description: 'Test description',
status: 'pending' as const,
priority: 'high' as const,
dependencies: [],
details: 'Implementation details',
testStrategy: 'Unit tests',
subtasks: []
};
// Access protected method through any type assertion for testing
const formattedPrompt = (executor as any).formatTaskPrompt(mockTask);
expect(formattedPrompt).toContain('Task ID: 1');
expect(formattedPrompt).toContain('Title: Test Task');
expect(formattedPrompt).toContain('Description:\nTest description');
expect(formattedPrompt).toContain(
'Implementation Details:\nImplementation details'
);
expect(formattedPrompt).toContain('Test Strategy:\nUnit tests');
expect(formattedPrompt).toContain('Status: pending');
expect(formattedPrompt).toContain('Priority: high');
});
});