Skip to content
Open
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
81 changes: 29 additions & 52 deletions src/world_modeling/prediction/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,73 +26,50 @@ endif()
# ---- General ROS 2 Packages
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)

# ---- Msg Packages
find_package(common_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(vision_msgs REQUIRED)

find_package(Eigen3 REQUIRED)

# Compiles source files into a library
# A library is not executed, instead other executables can link
# against it to access defined methods and classes.
# We build a library so that the methods defined can be used by
# both the unit test and ROS2 node executables.
add_library(prediction_lib
src/utils.cpp
src/trajectory_predictor.cpp
src/intent_classifier.cpp
src/motion_models.cpp
src/map_interface.cpp
)

# Indicate to compiler where to search for header files
set_target_properties(prediction_lib PROPERTIES POSITION_INDEPENDENT_CODE ON)

target_include_directories(prediction_lib
PUBLIC
include)
include
${EIGEN3_INCLUDE_DIR})

# Add ROS2 dependencies required by package
ament_target_dependencies(prediction_lib
rclcpp
common_msgs
# Link ROS2 dependencies required by package
target_link_libraries(prediction_lib
rclcpp::rclcpp
rclcpp_components::component
${std_msgs_TARGETS}
${geometry_msgs_TARGETS}
${vision_msgs_TARGETS}
Eigen3::Eigen
)

# # By default tests are built. This can be overridden by modifying the
# # colcon build command to include the -DBUILD_TESTING=OFF flag.
# option(BUILD_TESTING "Build tests" ON)
# if(BUILD_TESTING)
# # Search for dependencies required for building tests + linting
# find_package(ament_cmake_gtest REQUIRED)
# find_package(ament_lint_auto REQUIRED)
# find_package(ament_lint_common REQUIRED)
#
# # Remove the default C++ and copyright linter
# list(APPEND AMENT_LINT_AUTO_EXCLUDE
# ament_cmake_cpplint
# ament_cmake_copyright)
#
# # Reinstall cpplint ignoring copyright errors
# ament_cpplint(FILTERS "-legal/copyright")
#
# ament_lint_auto_find_test_dependencies()
#
# # Create test executable from source files
# ament_add_gtest(sample_test test/sample_test.cpp)
# # Link to the previously built library to access Sample classes and methods
# target_link_libraries(sample_test
# kalman_filter_lib
# gtest_main)
#
# # Copy executable to installation location
# install(TARGETS
# sample_test
# DESTINATION lib/${PROJECT_NAME})
# endif()

# Create ROS2 node executable from source files
add_executable(prediction_node src/kalman_filter.cpp)
# Link to the previously built library to access Sample classes and methods
add_library(prediction_node SHARED src/prediction_node.cpp)
target_link_libraries(prediction_node prediction_lib)
rclcpp_components_register_nodes(prediction_node "prediction::PredictionNode")

# Copy executable to installation location
install(TARGETS
prediction_node
DESTINATION lib/${PROJECT_NAME})
prediction_lib
prediction_node
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

# Copy launch and config files to installation location
install(DIRECTORY
config
launch
Expand Down
91 changes: 91 additions & 0 deletions src/world_modeling/prediction/DEVELOPING.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
# Prediction Module - Developer Guide

## File Structure Rationale

Component-based architecture enabling parallel development:

```
prediction_node.cpp β†’ ROS orchestrator (no algorithm logic)
trajectory_predictor.cpp β†’ Strategy pattern (select algorithm by object type)
motion_models.cpp β†’ Pure functions (physics-based state propagation)
intent_classifier.cpp β†’ Probability assignment (independent of trajectories)
map_interface.cpp β†’ Adapter for HD map services (currently placeholders)
```

**Why this structure?**
- **Separation of concerns**: Each file has one responsibility
- **Parallel work**: Person 1, 2, 3 modify different functions (no conflicts)
- **Testability**: Components tested independently
- **Extensibility**: Add new models/object types without changing existing code

## Implementation Details

### Placeholder Mode

Map services not required during development. Placeholders return:
- Deterministic lanelet IDs based on grid position
- Synthetic straight centerlines
- Mock crosswalk locations at grid intersections

**To switch to real map services**: Uncomment service client code in `MapInterface` constructor in `src/map_interface.cpp`.

### Output Format

All trajectory generators must return `std::vector<TrajectoryHypothesis>`:

```cpp
TrajectoryHypothesis hyp;
hyp.waypoints = /* std::vector<geometry_msgs::msg::Pose> */;
hyp.timestamps = /* std::vector<double> matching waypoints length */;
hyp.intent = Intent::CONTINUE_STRAIGHT; // or other intent enum
hyp.probability = 0.0; // Classifier sets this later
```

**Critical**: All three team members must use identical output format.

### Map Interface API

Available to all team members:

```cpp
// Get current lane
int64_t lanelet = map_interface_->findNearestLanelet(position);

// Get reachable future lanes
auto futures = map_interface_->getPossibleFutureLanelets(lanelet, depth);

// Get centerline for path following
LaneletInfo info = map_interface_->getLaneletById(lanelet);
std::vector<geometry_msgs::msg::Point> centerline = info.centerline;

// Check for crosswalk
bool crosswalk = map_interface_->isCrosswalkNearby(position, radius);
```

## Testing

```bash
# Build
colcon build --packages-select prediction

# Run with debug logs
ros2 launch prediction prediction.launch.py --ros-args --log-level debug

# Publish test detection
ros2 topic pub /perception/detections_3D_tracked vision_msgs/msg/Detection3DArray "..."
```

## Adding Dependencies

Follow monorepo guidelines in `/tmp/wato_monorepo/DEVELOPING.md`:
1. Prefer ROSdep dependencies (add to `package.xml`)
2. System packages only if no ROSdep key exists
3. Consider contributing to rosdistro for missing packages

## Future Enhancements

- Replace physics-based models with learned models
- Add ML-based intent classifier
- Support for additional object types (trucks, motorcycles)
- Integration with tracking history for velocity estimation
- Turn signal observation from CAN bus
107 changes: 107 additions & 0 deletions src/world_modeling/prediction/PR_DESCRIPTION.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
# Pull Request: Prediction Module Skeleton

## Overview
Complete skeleton implementation for multi-modal trajectory prediction system. Ready for team members to implement their assigned components.

## What's Included

### Architecture
- **Component-based design** enabling parallel development
- **Prediction Node**: ROS orchestrator (no merge conflicts)
- **Trajectory Predictor**: Strategy pattern for different object types
- **Motion Models**: Physics-based kinematics (bicycle, constant velocity)
- **Intent Classifier**: Probability assignment (shared by all)
- **Map Interface**: HD map queries with placeholders

### Team Tasks
- **Girish**: Pedestrian prediction (`generatePedestrianHypotheses` + constant velocity with noise)
- **John**: Vehicle prediction (`generateVehicleHypotheses` + bicycle model path following)
- **Aruhant**: Cyclist prediction (`generateCyclistHypotheses` + hybrid model)

### Key Features
- βœ… Builds successfully with `colcon build --packages-select prediction`
- βœ… Runs standalone without map services (placeholder mode)
- βœ… Clear task markers in code (`// GIRISH TASK:`, `// JOHN TASK:`, `// ARUHANT TASK:`)
- βœ… Consistent output format enforced across all implementations
- βœ… Full ROS 2 integration (subscribers, publishers, parameters)
- βœ… Comprehensive documentation (README + DEVELOPING.md)

## File Structure

```
prediction/
β”œβ”€β”€ README.md # User-facing overview and quick start
β”œβ”€β”€ DEVELOPING.md # Technical details and architecture rationale
β”œβ”€β”€ CMakeLists.txt # Build configuration
β”œβ”€β”€ package.xml # ROS package manifest
β”œβ”€β”€ config/
β”‚ └── params.yaml # Tunable parameters
β”œβ”€β”€ include/prediction/ # Header files (interfaces)
β”‚ β”œβ”€β”€ prediction_node.hpp
β”‚ β”œβ”€β”€ trajectory_predictor.hpp
β”‚ β”œβ”€β”€ motion_models.hpp
β”‚ β”œβ”€β”€ intent_classifier.hpp
β”‚ └── map_interface.hpp
β”œβ”€β”€ src/ # Implementation files
β”‚ β”œβ”€β”€ prediction_node.cpp
β”‚ β”œβ”€β”€ trajectory_predictor.cpp
β”‚ β”œβ”€β”€ motion_models.cpp
β”‚ β”œβ”€β”€ intent_classifier.cpp
β”‚ └── map_interface.cpp
└── launch/
└── prediction.launch.py
```

## Changes from Previous Version
- ❌ Removed old Kalman filter implementation
- βœ… Added complete prediction pipeline structure
- βœ… Added placeholder implementations (no external dependencies)
- βœ… Simplified documentation (removed redundant files)
- βœ… Fixed build issues (removed non-existent wato_msgs dependency)

## Documentation
- **README.md**: Quick overview, ROS interface, team tasks
- **DEVELOPING.md**: Architecture rationale, implementation details, testing

## Current Status
- **Buildable**: No compilation errors
- **Runnable**: Standalone mode with placeholders
- **Testable**: Can publish mock detections and observe behavior
- **Ready for implementation**: Clear TODOs for each team member

## Next Steps for Team
1. Each person implements their assigned function
2. Coordinate on output format (critical!)
3. Test with mock detections
4. When map services ready: uncomment service clients in `map_interface.cpp`
5. Define message types in `world_modeling_msgs`

## Testing

```bash
# Build
colcon build --packages-select prediction

# Run
ros2 launch prediction prediction.launch.py

# Test with mock detection
ros2 topic pub /perception/detections_3D_tracked vision_msgs/msg/Detection3DArray "..."
```

## Dependencies
- ROS 2 Humble
- vision_msgs
- geometry_msgs
- Eigen3
- No external map services required (placeholders)

## Notes
- Map interface uses placeholders (synthetic data) until services available
- Output format enforced through `TrajectoryHypothesis` struct
- All team members work in isolated functions (parallel development)
- Intent classifier shared by all (no modifications needed)

---

**Ready for review and team implementation!** πŸš€
Loading
Loading