Class OperationManager
Defined in File operation_manager.hpp
Nested Relationships
Nested Types
Class Documentation
-
class OperationManager
Manager for ROS2 operations (services and actions) Handles service calls synchronously and action calls asynchronously
Public Functions
-
explicit OperationManager(rclcpp::Node *node, DiscoveryManager *discovery_manager)
-
~OperationManager()
-
void shutdown()
Explicitly release subscriptions, clients, and tracked goals. Call while executor is still running to allow safe callback cleanup. Called automatically by destructor, but GatewayNode calls it earlier during its shutdown sequence.
-
void set_notifier(ResourceChangeNotifier *notifier)
Set optional notifier for broadcasting operation status changes to trigger subsystem.
-
ServiceCallResult call_service(const std::string &service_path, const std::string &service_type, const json &request)
Call a ROS2 service synchronously
- Parameters:
service_path – Full service path (e.g., “/powertrain/engine/calibrate”)
service_type – Service type (e.g., “std_srvs/srv/Trigger”)
request – JSON request body
- Returns:
ServiceCallResult with response or error
-
ServiceCallResult call_component_service(const std::string &component_ns, const std::string &operation_name, const std::optional<std::string> &service_type, const json &request)
Find and call a service by component and operation name Uses discovery cache to resolve service path and type if not provided
- Parameters:
component_ns – Component namespace (e.g., “/powertrain/engine”)
operation_name – Operation name (e.g., “calibrate”)
service_type – Optional service type override
request – JSON request body
- Returns:
ServiceCallResult with response or error
-
ActionSendGoalResult send_action_goal(const std::string &action_path, const std::string &action_type, const json &goal, const std::string &entity_id = "")
Send a goal to an action server using native rclcpp_action internal services
- Parameters:
action_path – Full action path (e.g., “/powertrain/engine/long_calibration”)
action_type – Action type (e.g., “example_interfaces/action/Fibonacci”)
goal – JSON goal data
entity_id – SOVD entity ID for trigger notifications (e.g., “engine”)
- Returns:
ActionSendGoalResult with goal_id or error
-
ActionSendGoalResult send_component_action_goal(const std::string &component_ns, const std::string &operation_name, const std::optional<std::string> &action_type, const json &goal, const std::string &entity_id = "")
Send a goal to an action using component namespace and operation name Uses discovery cache to resolve action path and type if not provided
- Parameters:
component_ns – Component namespace (e.g., “/powertrain/engine”)
operation_name – Operation name (e.g., “long_calibration”)
action_type – Optional action type override
goal – JSON goal data
entity_id – SOVD entity ID for trigger notifications (e.g., “engine”)
- Returns:
ActionSendGoalResult with goal_id or error
-
ActionCancelResult cancel_action_goal(const std::string &action_path, const std::string &goal_id)
Cancel a running action goal using ros2 action cancel
- Parameters:
action_path – Full action path
goal_id – Goal UUID hex string
- Returns:
-
ActionGetResultResult get_action_result(const std::string &action_path, const std::string &action_type, const std::string &goal_id)
Get the result of a completed action This is a blocking call that waits for the action to complete
- Parameters:
action_path – Full action path
action_type – Action type
goal_id – Goal UUID hex string
- Returns:
ActionGetResultResult with result or error
-
std::optional<ActionGoalInfo> get_tracked_goal(const std::string &goal_id) const
Get tracked goal info by goal_id
- Parameters:
goal_id – Goal UUID hex string
- Returns:
Optional ActionGoalInfo if found
-
std::vector<ActionGoalInfo> list_tracked_goals() const
List all tracked goals
- Returns:
Vector of all tracked goals
-
std::vector<ActionGoalInfo> get_goals_for_action(const std::string &action_path) const
Get all goals for a specific action path
- Parameters:
action_path – Full action path (e.g., “/powertrain/engine/long_calibration”)
- Returns:
Vector of goals for that action, sorted by last_update (newest first)
-
std::optional<ActionGoalInfo> get_latest_goal_for_action(const std::string &action_path) const
Get the most recent goal for a specific action path
- Parameters:
action_path – Full action path
- Returns:
Optional ActionGoalInfo if any goal exists for this action
-
void update_goal_status(const std::string &goal_id, ActionGoalStatus status)
Update goal status in tracking
- Parameters:
goal_id – Goal UUID hex string
status – New status
-
void update_goal_feedback(const std::string &goal_id, const json &feedback)
Update goal feedback in tracking
- Parameters:
goal_id – Goal UUID hex string
feedback – New feedback JSON
-
void cleanup_old_goals(std::chrono::seconds max_age = std::chrono::seconds(300))
Remove completed goals older than specified duration
- Parameters:
max_age – Maximum age of completed goals to keep
-
void subscribe_to_action_status(const std::string &action_path)
Subscribe to action status topic for real-time updates Called automatically when a goal is sent
- Parameters:
action_path – Full action path (e.g., “/powertrain/engine/long_calibration”)
-
void unsubscribe_from_action_status(const std::string &action_path)
Unsubscribe from action status topic Called when no more active goals exist for this action
- Parameters:
action_path – Full action path
Public Static Functions
-
static bool is_valid_message_type(const std::string &type)
Validate message type format (package/srv/Type or package/action/Type)
-
static bool is_valid_uuid_hex(const std::string &uuid_hex)
Validate UUID hex string format (32 hex characters)
-
static bool is_service_type(const std::string &type)
Check if type is a service type (contains /srv/)
-
static bool is_action_type(const std::string &type)
Check if type is an action type (contains /action/)
-
explicit OperationManager(rclcpp::Node *node, DiscoveryManager *discovery_manager)