autocore_std/lib.rs
1//! # AutoCore Standard Library
2//!
3//! The standard library for writing AutoCore control programs. This crate provides
4//! everything you need to build real-time control applications that integrate with
5//! the AutoCore server ecosystem.
6//!
7//! ## Overview
8//!
9//! AutoCore control programs run as separate processes that communicate with the
10//! autocore-server via shared memory and IPC. This library handles all the low-level
11//! details, allowing you to focus on your control logic.
12//!
13//! ```text
14//! ┌─────────────────────────┐ ┌─────────────────────────┐
15//! │ autocore-server │ │ Your Control Program │
16//! │ │ │ │
17//! │ ┌─────────────────┐ │ │ ┌─────────────────┐ │
18//! │ │ Shared Memory │◄───┼─────┼──│ ControlRunner │ │
19//! │ │ (GlobalMemory) │ │ │ │ │ │
20//! │ └─────────────────┘ │ │ │ ┌─────────────┐ │ │
21//! │ │ │ │ │ Your Logic │ │ │
22//! │ ┌─────────────────┐ │ │ │ └─────────────┘ │ │
23//! │ │ Tick Signal │────┼─────┼──│ │ │
24//! │ └─────────────────┘ │ │ └─────────────────┘ │
25//! └─────────────────────────┘ └─────────────────────────┘
26//! ```
27//!
28//! ## Quick Start
29//!
30//! 1. Create a new control project using `acctl`:
31//! ```bash
32//! acctl clone <server-ip> <project-name>
33//! ```
34//!
35//! 2. Implement the [`ControlProgram`] trait:
36//! ```ignore
37//! use autocore_std::{ControlProgram, TickContext};
38//! use autocore_std::fb::RTrig;
39//!
40//! // GlobalMemory is generated from your project.json
41//! mod gm;
42//! use gm::GlobalMemory;
43//!
44//! pub struct MyProgram {
45//! start_button: RTrig,
46//! }
47//!
48//! impl MyProgram {
49//! pub fn new() -> Self {
50//! Self {
51//! start_button: RTrig::new(),
52//! }
53//! }
54//! }
55//!
56//! impl ControlProgram for MyProgram {
57//! type Memory = GlobalMemory;
58//!
59//! fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
60//! // Detect rising edge on start button
61//! if self.start_button.call(ctx.gm.inputs.start_button) {
62//! ctx.gm.outputs.motor_running = true;
63//! autocore_std::log::info!("Motor started!");
64//! }
65//! }
66//! }
67//! ```
68//!
69//! 3. Use the [`autocore_main!`] macro for the entry point:
70//! ```ignore
71//! autocore_std::autocore_main!(MyProgram, "my_project_shm", "tick");
72//! ```
73//!
74//! ## Function Blocks (IEC 61131-3 Inspired)
75//!
76//! This library includes standard function blocks commonly used in PLC programming:
77//!
78//! - [`fb::RTrig`] - Rising edge detector (false→true transition)
79//! - [`fb::FTrig`] - Falling edge detector (true→false transition)
80//! - [`fb::Ton`] - Timer On Delay (output after delay)
81//! - [`fb::BitResetOnDelay`] - Resets a boolean after it has been true for a duration
82//! - [`fb::SimpleTimer`] - Simple one-shot timer (NOT IEC 61131-3, for imperative use)
83//! - [`fb::StateMachine`] - State machine helper with automatic timer management
84//! - [`fb::RunningAverage`] - Accumulates values and computes their arithmetic mean
85//! - [`fb::Beeper`] - Audible beeper controller with configurable beep sequences
86//! - [`fb::Heartbeat`] - Monitors a remote heartbeat counter for connection loss
87//!
88//! ### Example: Edge Detection
89//!
90//! ```
91//! use autocore_std::fb::RTrig;
92//!
93//! let mut trigger = RTrig::new();
94//!
95//! // First call with false - no edge
96//! assert_eq!(trigger.call(false), false);
97//!
98//! // Rising edge detected!
99//! assert_eq!(trigger.call(true), true);
100//!
101//! // Still true, but no edge (already high)
102//! assert_eq!(trigger.call(true), false);
103//!
104//! // Back to false
105//! assert_eq!(trigger.call(false), false);
106//!
107//! // Another rising edge
108//! assert_eq!(trigger.call(true), true);
109//! ```
110//!
111//! ### Example: Timer
112//!
113//! ```
114//! use autocore_std::fb::Ton;
115//! use std::time::Duration;
116//!
117//! let mut timer = Ton::new();
118//! let delay = Duration::from_millis(100);
119//!
120//! // Timer not enabled - output is false
121//! assert_eq!(timer.call(false, delay), false);
122//!
123//! // Enable timer - starts counting
124//! assert_eq!(timer.call(true, delay), false);
125//!
126//! // Still counting...
127//! std::thread::sleep(Duration::from_millis(50));
128//! assert_eq!(timer.call(true, delay), false);
129//! assert!(timer.et < delay); // Elapsed time < preset
130//!
131//! // After delay elapsed
132//! std::thread::sleep(Duration::from_millis(60));
133//! assert_eq!(timer.call(true, delay), true); // Output is now true!
134//! ```
135//!
136//! ## Logging
137//!
138//! Control programs can send log messages to the autocore-server for display in the
139//! web console. Logging is handled automatically when using [`ControlRunner`].
140//!
141//! ```ignore
142//! use autocore_std::log;
143//!
144//! log::trace!("Detailed trace message");
145//! log::debug!("Debug information");
146//! log::info!("Normal operation message");
147//! log::warn!("Warning condition detected");
148//! log::error!("Error occurred!");
149//! ```
150//!
151//! See the [`logger`] module for advanced configuration.
152//!
153//! ## Memory Synchronization
154//!
155//! The [`ControlRunner`] handles all shared memory synchronization automatically:
156//!
157//! 1. **Wait for tick** - Blocks until the server signals a new cycle
158//! 2. **Read inputs** - Copies shared memory to local buffer (atomic snapshot)
159//! 3. **Execute logic** - Your `process_tick` runs on the local buffer
160//! 4. **Write outputs** - Copies local buffer back to shared memory
161//!
162//! This ensures your control logic always sees a consistent view of the data,
163//! even when other processes are modifying shared memory.
164
165#![warn(missing_docs)]
166#![warn(rustdoc::missing_crate_level_docs)]
167#![doc(html_root_url = "https://docs.rs/autocore-std/3.3.0")]
168
169use anyhow::{anyhow, Result};
170use futures_util::{SinkExt, StreamExt};
171use log::LevelFilter;
172use mechutil::ipc::{CommandMessage, MessageType};
173use raw_sync::events::{Event, EventInit, EventState};
174use raw_sync::Timeout;
175use shared_memory::ShmemConf;
176use std::collections::HashMap;
177use std::sync::atomic::{fence, Ordering, AtomicBool};
178use std::sync::Arc;
179use std::time::Duration;
180use tokio_tungstenite::{connect_async, tungstenite::Message};
181
182/// UDP logger for sending log messages to autocore-server.
183///
184/// This module provides a non-blocking logger implementation that sends log messages
185/// via UDP to the autocore-server. Messages are batched and sent asynchronously to
186/// avoid impacting the control loop timing.
187///
188/// # Example
189///
190/// ```ignore
191/// use autocore_std::logger;
192/// use log::LevelFilter;
193///
194/// // Initialize the logger (done automatically by ControlRunner)
195/// logger::init_udp_logger("127.0.0.1", 39101, LevelFilter::Info, "control")?;
196///
197/// // Now you can use the log macros
198/// log::info!("System initialized");
199/// ```
200pub mod logger;
201
202// Re-export log crate for convenience - control programs can use autocore_std::log::info!() etc.
203pub use log;
204
205/// Function blocks for control programs (IEC 61131-3 inspired).
206pub mod fb;
207
208/// Interface protocols for communication between control programs and external sources.
209pub mod iface;
210
211/// Client for sending IPC commands to external modules via WebSocket.
212pub mod command_client;
213pub use command_client::CommandClient;
214
215/// EtherCAT utilities (SDO client, etc.).
216pub mod ethercat;
217
218/// CiA 402 motion control: axis abstraction, traits, and types.
219pub mod motion;
220
221/// Shared memory utilities for external modules.
222pub mod shm;
223
224/// Lightweight process diagnostics (FD count, RSS).
225pub mod diagnostics;
226
227// ============================================================================
228// Core Framework
229// ============================================================================
230
231/// Marker trait for generated GlobalMemory structs.
232///
233/// This trait is implemented by the auto-generated `GlobalMemory` struct
234/// that represents the shared memory layout. It serves as a marker for
235/// type safety in the control framework.
236///
237/// You don't need to implement this trait yourself - it's automatically
238/// implemented by the code generator.
239pub trait AutoCoreMemory {}
240
241/// Trait for detecting changes in memory structures.
242pub trait ChangeTracker {
243 /// Compare self with a previous state and return a list of changed fields.
244 /// Returns a vector of (field_name, new_value).
245 fn get_changes(&self, prev: &Self) -> Vec<(&'static str, serde_json::Value)>;
246}
247
248/// Per-tick context passed to the control program by the framework.
249///
250/// `TickContext` bundles all per-cycle data into a single struct so that the
251/// [`ControlProgram::process_tick`] signature stays stable as new fields are
252/// added in the future (e.g., delta time, diagnostics).
253///
254/// The framework constructs a fresh `TickContext` each cycle, calls
255/// [`CommandClient::poll`] before handing it to the program, and writes
256/// the memory back to shared memory after `process_tick` returns.
257pub struct TickContext<'a, M> {
258 /// Mutable reference to the local shared memory copy.
259 pub gm: &'a mut M,
260 /// IPC command client for communicating with external modules.
261 pub client: &'a mut CommandClient,
262 /// Current cycle number (starts at 1, increments each tick).
263 pub cycle: u64,
264}
265
266/// The trait that defines a control program's logic.
267///
268/// Implement this trait to create your control program. The associated `Memory`
269/// type should be the generated `GlobalMemory` struct from your project.
270///
271/// # Memory Type Requirements
272///
273/// The `Memory` type must implement `Copy` to allow efficient synchronization
274/// between shared memory and local buffers. This is automatically satisfied
275/// by the generated `GlobalMemory` struct.
276///
277/// # Lifecycle
278///
279/// 1. `initialize` is called once at startup
280/// 2. `process_tick` is called repeatedly in the control loop with a
281/// [`TickContext`] that provides shared memory, the IPC client, and the
282/// current cycle number.
283///
284/// # Example
285///
286/// ```ignore
287/// use autocore_std::{ControlProgram, TickContext};
288///
289/// mod gm;
290/// use gm::GlobalMemory;
291///
292/// pub struct MyController {
293/// cycle_counter: u64,
294/// }
295///
296/// impl MyController {
297/// pub fn new() -> Self {
298/// Self { cycle_counter: 0 }
299/// }
300/// }
301///
302/// impl ControlProgram for MyController {
303/// type Memory = GlobalMemory;
304///
305/// fn initialize(&mut self, mem: &mut GlobalMemory) {
306/// // Set initial output states
307/// mem.outputs.ready = true;
308/// log::info!("Controller initialized");
309/// }
310///
311/// fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
312/// self.cycle_counter = ctx.cycle;
313///
314/// // Your control logic here
315/// if ctx.gm.inputs.start && !ctx.gm.inputs.estop {
316/// ctx.gm.outputs.running = true;
317/// }
318/// }
319/// }
320/// ```
321pub trait ControlProgram {
322 /// The shared memory structure type (usually the generated `GlobalMemory`).
323 ///
324 /// Must implement `Copy` to allow efficient memory synchronization.
325 type Memory: Copy + ChangeTracker;
326
327 /// Called once when the control program starts.
328 ///
329 /// Use this to initialize output states, reset counters, or perform
330 /// any one-time setup. The default implementation does nothing.
331 ///
332 /// # Arguments
333 ///
334 /// * `mem` - Mutable reference to the shared memory. Changes are written
335 /// back to shared memory after this method returns.
336 fn initialize(&mut self, _mem: &mut Self::Memory) {}
337
338 /// The main control loop - called once per scan cycle.
339 ///
340 /// This is where your control logic lives. Read inputs from `ctx.gm`,
341 /// perform calculations, and write outputs back to `ctx.gm`. Use
342 /// `ctx.client` for IPC commands and `ctx.cycle` for the current cycle
343 /// number.
344 ///
345 /// The framework calls [`CommandClient::poll`] before each invocation,
346 /// so incoming responses are already buffered when your code runs.
347 ///
348 /// # Arguments
349 ///
350 /// * `ctx` - A [`TickContext`] containing the local shared memory copy,
351 /// the IPC command client, and the current cycle number.
352 ///
353 /// # Timing
354 ///
355 /// This method should complete within the scan cycle time. Long-running
356 /// operations will cause cycle overruns.
357 fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>);
358}
359
360/// Configuration for the [`ControlRunner`].
361///
362/// Specifies connection parameters, shared memory names, and logging settings.
363/// Use [`Default::default()`] for typical configurations.
364///
365/// # Example
366///
367/// ```
368/// use autocore_std::RunnerConfig;
369/// use log::LevelFilter;
370///
371/// let config = RunnerConfig {
372/// server_host: "192.168.1.100".to_string(),
373/// module_name: "my_controller".to_string(),
374/// shm_name: "my_project_shm".to_string(),
375/// tick_signal_name: "tick".to_string(),
376/// busy_signal_name: Some("busy".to_string()),
377/// log_level: LevelFilter::Debug,
378/// ..Default::default()
379/// };
380/// ```
381#[derive(Debug, Clone)]
382pub struct RunnerConfig {
383 /// Server host address (default: "127.0.0.1")
384 pub server_host: String,
385 /// WebSocket port for commands (default: 11969)
386 pub ws_port: u16,
387 /// Module name for identification (default: "control")
388 pub module_name: String,
389 /// Shared memory segment name (must match server configuration)
390 pub shm_name: String,
391 /// Name of the tick signal in shared memory (triggers each scan cycle)
392 pub tick_signal_name: String,
393 /// Optional name of the busy signal (set when cycle completes)
394 pub busy_signal_name: Option<String>,
395 /// Minimum log level to send to the server (default: Info)
396 pub log_level: LevelFilter,
397 /// UDP port for sending logs to the server (default: 39101)
398 pub log_udp_port: u16,
399}
400
401/// Default WebSocket port for autocore-server
402pub const DEFAULT_WS_PORT: u16 = 11969;
403
404impl Default for RunnerConfig {
405 fn default() -> Self {
406 Self {
407 server_host: "127.0.0.1".to_string(),
408 ws_port: DEFAULT_WS_PORT,
409 module_name: "control".to_string(),
410 shm_name: "autocore_cyclic".to_string(),
411 tick_signal_name: "tick".to_string(),
412 busy_signal_name: None,
413 log_level: LevelFilter::Info,
414 log_udp_port: logger::DEFAULT_LOG_UDP_PORT,
415 }
416 }
417}
418
419
420/// The main execution engine for control programs.
421///
422/// `ControlRunner` handles all the infrastructure required to run a control program:
423///
424/// - Reading memory layout from the server's layout file
425/// - Opening and mapping shared memory
426/// - Setting up synchronization signals
427/// - Running the real-time control loop
428/// - Sending log messages to the server
429///
430/// # Usage
431///
432/// ```ignore
433/// use autocore_std::{ControlRunner, RunnerConfig};
434///
435/// let config = RunnerConfig {
436/// shm_name: "my_project_shm".to_string(),
437/// tick_signal_name: "tick".to_string(),
438/// ..Default::default()
439/// };
440///
441/// ControlRunner::new(MyProgram::new())
442/// .config(config)
443/// .run()?; // Blocks forever
444/// ```
445///
446/// # Control Loop
447///
448/// The runner executes a synchronous control loop:
449///
450/// 1. **Wait** - Blocks until the tick signal is set by the server
451/// 2. **Read** - Copies shared memory to a local buffer (acquire barrier)
452/// 3. **Execute** - Calls your `process_tick` method
453/// 4. **Write** - Copies local buffer back to shared memory (release barrier)
454/// 5. **Signal** - Sets the busy signal (if configured) to indicate completion
455///
456/// This ensures your code always sees a consistent snapshot of the data
457/// and that your writes are atomically visible to other processes.
458pub struct ControlRunner<P: ControlProgram> {
459 config: RunnerConfig,
460 program: P,
461}
462
463impl<P: ControlProgram> ControlRunner<P> {
464 /// Creates a new runner for the given control program.
465 ///
466 /// Uses default configuration. Call [`.config()`](Self::config) to customize.
467 ///
468 /// # Arguments
469 ///
470 /// * `program` - Your control program instance
471 ///
472 /// # Example
473 ///
474 /// ```ignore
475 /// let runner = ControlRunner::new(MyProgram::new());
476 /// ```
477 pub fn new(program: P) -> Self {
478 Self {
479 config: RunnerConfig::default(),
480 program,
481 }
482 }
483
484 /// Sets the configuration for this runner.
485 ///
486 /// # Arguments
487 ///
488 /// * `config` - The configuration to use
489 ///
490 /// # Example
491 ///
492 /// ```ignore
493 /// ControlRunner::new(MyProgram::new())
494 /// .config(RunnerConfig {
495 /// shm_name: "custom_shm".to_string(),
496 /// ..Default::default()
497 /// })
498 /// .run()?;
499 /// ```
500 pub fn config(mut self, config: RunnerConfig) -> Self {
501 self.config = config;
502 self
503 }
504
505 /// Starts the control loop.
506 ///
507 /// This method blocks indefinitely, running the control loop until
508 /// an error occurs or the process is terminated.
509 ///
510 /// # Returns
511 ///
512 /// Returns `Ok(())` only if the loop exits cleanly (which typically
513 /// doesn't happen). Returns an error if:
514 ///
515 /// - IPC connection fails
516 /// - Shared memory cannot be opened
517 /// - Signal offsets cannot be found
518 /// - A critical error occurs during execution
519 ///
520 /// # Example
521 ///
522 /// ```ignore
523 /// fn main() -> anyhow::Result<()> {
524 /// ControlRunner::new(MyProgram::new())
525 /// .config(config)
526 /// .run()
527 /// }
528 /// ```
529 pub fn run(mut self) -> Result<()> {
530 // Initialize UDP logger FIRST (before any log statements)
531 if let Err(e) = logger::init_udp_logger(
532 &self.config.server_host,
533 self.config.log_udp_port,
534 self.config.log_level,
535 "control",
536 ) {
537 eprintln!("Warning: Failed to initialize UDP logger: {}", e);
538 // Continue anyway - logging will just go nowhere
539 }
540
541 // Multi-threaded runtime so spawned WS read/write tasks can run
542 // alongside the synchronous control loop.
543 let rt = tokio::runtime::Builder::new_multi_thread()
544 .worker_threads(2)
545 .enable_all()
546 .build()?;
547
548 rt.block_on(async {
549 log::info!("AutoCore Control Runner Starting...");
550
551 // 1. Connect to server via WebSocket and get layout
552 let ws_url = format!("ws://{}:{}/ws/", self.config.server_host, self.config.ws_port);
553 log::info!("Connecting to server at {}", ws_url);
554
555 let (ws_stream, _) = connect_async(&ws_url).await
556 .map_err(|e| anyhow!("Failed to connect to server at {}: {}", ws_url, e))?;
557
558 let (mut write, mut read) = ws_stream.split();
559
560 // Send gm.get_layout request
561 let request = CommandMessage::request("gm.get_layout", serde_json::Value::Null);
562 let transaction_id = request.transaction_id;
563 let request_json = serde_json::to_string(&request)?;
564
565 write.send(Message::Text(request_json)).await
566 .map_err(|e| anyhow!("Failed to send layout request: {}", e))?;
567
568 // Wait for response with matching transaction_id
569 let timeout = Duration::from_secs(10);
570 let start = std::time::Instant::now();
571 let mut layout: Option<HashMap<String, serde_json::Value>> = None;
572
573 while start.elapsed() < timeout {
574 match tokio::time::timeout(Duration::from_secs(1), read.next()).await {
575 Ok(Some(Ok(Message::Text(text)))) => {
576 if let Ok(response) = serde_json::from_str::<CommandMessage>(&text) {
577 if response.transaction_id == transaction_id {
578 if !response.success {
579 return Err(anyhow!("Server error: {}", response.error_message));
580 }
581 layout = Some(serde_json::from_value(response.data)?);
582 break;
583 }
584 // Skip broadcasts and other messages
585 if response.message_type == MessageType::Broadcast {
586 continue;
587 }
588 }
589 }
590 Ok(Some(Ok(_))) => continue,
591 Ok(Some(Err(e))) => return Err(anyhow!("WebSocket error: {}", e)),
592 Ok(None) => return Err(anyhow!("Server closed connection")),
593 Err(_) => continue, // Timeout on single read, keep trying
594 }
595 }
596
597 let layout = layout.ok_or_else(|| anyhow!("Timeout waiting for layout response"))?;
598 log::info!("Layout received with {} entries.", layout.len());
599
600 // Set up channels and background tasks for shared WebSocket access.
601 // This allows both the control loop (gm.write) and CommandClient (IPC
602 // commands) to share the write half, while routing incoming responses
603 // to the CommandClient.
604 let (ws_write_tx, mut ws_write_rx) = tokio::sync::mpsc::unbounded_channel::<String>();
605 let (response_tx, response_rx) = tokio::sync::mpsc::unbounded_channel::<CommandMessage>();
606
607 // Background task: WS write loop
608 // Reads serialized messages from ws_write_rx and sends them over the WebSocket.
609 tokio::spawn(async move {
610 while let Some(msg_json) = ws_write_rx.recv().await {
611 if let Err(e) = write.send(Message::Text(msg_json)).await {
612 log::error!("WebSocket write error: {}", e);
613 break;
614 }
615 }
616 });
617
618 // Background task: WS read loop
619 // Reads all incoming WebSocket messages. Routes Response messages to
620 // response_tx for the CommandClient; ignores broadcasts and others.
621 tokio::spawn(async move {
622 while let Some(result) = read.next().await {
623 match result {
624 Ok(Message::Text(text)) => {
625 if let Ok(msg) = serde_json::from_str::<CommandMessage>(&text) {
626 if msg.message_type == MessageType::Response {
627 if response_tx.send(msg).is_err() {
628 break; // receiver dropped
629 }
630 }
631 // Broadcasts and other message types are ignored
632 }
633 }
634 Ok(Message::Close(_)) => {
635 log::info!("WebSocket closed by server");
636 break;
637 }
638 Err(e) => {
639 log::error!("WebSocket read error: {}", e);
640 break;
641 }
642 _ => {} // Ping/Pong/Binary - ignore
643 }
644 }
645 });
646
647 // Construct CommandClient — owned by the runner, passed to the
648 // program via TickContext each cycle.
649 let mut command_client = CommandClient::new(ws_write_tx.clone(), response_rx);
650
651 // 2. Find Signal Offsets
652 let tick_offset = self.find_offset(&layout, &self.config.tick_signal_name)?;
653 let busy_offset = if let Some(name) = &self.config.busy_signal_name {
654 Some(self.find_offset(&layout, name)?)
655 } else {
656 None
657 };
658
659 // 4. Open Shared Memory
660 let shmem = ShmemConf::new().os_id(&self.config.shm_name).open()?;
661 let base_ptr = shmem.as_ptr();
662 log::info!("Shared Memory '{}' mapped.", self.config.shm_name);
663
664 // 5. Setup Pointers
665 // SAFETY: We trust the server's layout matches the generated GlobalMemory struct.
666 let gm = unsafe { &mut *(base_ptr as *mut P::Memory) };
667
668 // Get tick event from shared memory
669 log::info!("Setting up tick event at offset {} (base_ptr: {:p})", tick_offset, base_ptr);
670 let (tick_event, _) = unsafe {
671 Event::from_existing(base_ptr.add(tick_offset))
672 }.map_err(|e| anyhow!("Failed to open tick event: {:?}", e))?;
673 log::info!("Tick event ready");
674
675 // Busy signal event (optional)
676 let busy_event = busy_offset.map(|offset| {
677 unsafe { Event::from_existing(base_ptr.add(offset)) }
678 .map(|(event, _)| event)
679 .ok()
680 }).flatten();
681
682 // 6. Initialize local memory buffer and user program
683 // We use a local copy for the control loop to ensure:
684 // - Consistent snapshot of inputs at start of cycle
685 // - Atomic commit of outputs at end of cycle
686 // - Proper memory barriers for cross-process visibility
687 let mut local_mem: P::Memory = unsafe { std::ptr::read_volatile(gm) };
688 let mut prev_mem: P::Memory = local_mem; // Snapshot for change detection
689
690 fence(Ordering::Acquire); // Ensure we see all prior writes from other processes
691
692 self.program.initialize(&mut local_mem);
693
694 // Write back any changes from initialize
695 fence(Ordering::Release);
696 unsafe { std::ptr::write_volatile(gm, local_mem) };
697
698 // Set up signal handler for graceful shutdown
699 let running = Arc::new(AtomicBool::new(true));
700 let r = running.clone();
701
702 // Only set handler if not already set
703 if let Err(e) = ctrlc::set_handler(move || {
704 r.store(false, Ordering::SeqCst);
705 }) {
706 log::warn!("Failed to set signal handler: {}", e);
707 }
708
709 log::info!("Entering Control Loop - waiting for first tick...");
710 let mut cycle_count: u64 = 0;
711 let mut consecutive_timeouts: u32 = 0;
712
713 while running.load(Ordering::SeqCst) {
714 // Wait for Tick - Event-based synchronization
715 // Use a timeout (1s) to allow checking the running flag periodically
716 match tick_event.wait(Timeout::Val(Duration::from_secs(1))) {
717 Ok(_) => {
718 consecutive_timeouts = 0;
719 },
720 Err(e) => {
721 // Check for timeout
722 let err_str = format!("{:?}", e);
723 if err_str.contains("Timeout") {
724 consecutive_timeouts += 1;
725 if consecutive_timeouts == 10 {
726 log::error!(
727 "TICK STALL: {} consecutive timeouts! cycle={} pending={} responses={} fds={} rss_kb={}",
728 consecutive_timeouts,
729 cycle_count,
730 command_client.pending_count(),
731 command_client.response_count(),
732 diagnostics::count_open_fds(),
733 diagnostics::get_rss_kb(),
734 );
735 }
736 if consecutive_timeouts > 10 && consecutive_timeouts % 60 == 0 {
737 log::error!(
738 "TICK STALL continues: {} consecutive timeouts, cycle={}",
739 consecutive_timeouts,
740 cycle_count,
741 );
742 }
743 continue;
744 }
745 return Err(anyhow!("Tick wait failed: {:?}", e));
746 }
747 }
748
749 if !running.load(Ordering::SeqCst) {
750 log::info!("Shutdown signal received, exiting control loop.");
751 break;
752 }
753
754 cycle_count += 1;
755 if cycle_count == 1 {
756 log::info!("First tick received!");
757 }
758
759 // // Periodic diagnostics (every 30s at 100 Hz)
760 // if cycle_count % 3000 == 0 {
761 // log::info!(
762 // "DIAG cycle={} pending={} responses={} fds={} rss_kb={}",
763 // cycle_count,
764 // command_client.pending_count(),
765 // command_client.response_count(),
766 // diagnostics::count_open_fds(),
767 // diagnostics::get_rss_kb(),
768 // );
769 // }
770
771 // === INPUT PHASE ===
772 // Read all variables from shared memory into local buffer.
773 // This gives us a consistent snapshot of inputs for this cycle.
774 // Acquire fence ensures we see all writes from other processes (server, modules).
775 local_mem = unsafe { std::ptr::read_volatile(gm) };
776
777 // Update prev_mem before execution to track changes made IN THIS CYCLE
778 // Actually, we want to know what changed in SHM relative to what we last knew,
779 // OR what WE changed relative to what we read?
780 // The user wants "writes on shared variables" to be broadcast.
781 // Typically outputs.
782 // If inputs changed (from other source), broadcasting them again is fine too.
783 // Let's capture state BEFORE execution (which is what we just read from SHM).
784 prev_mem = local_mem;
785
786 fence(Ordering::Acquire);
787
788 // === EXECUTE PHASE ===
789 // Poll IPC responses so they are available during process_tick.
790 command_client.poll();
791
792 // Execute user logic on the local copy.
793 // All reads/writes during process_tick operate on local_mem.
794 let mut ctx = TickContext {
795 gm: &mut local_mem,
796 client: &mut command_client,
797 cycle: cycle_count,
798 };
799 self.program.process_tick(&mut ctx);
800
801 // === OUTPUT PHASE ===
802 // Write all variables from local buffer back to shared memory.
803 // Release fence ensures our writes are visible to other processes.
804 fence(Ordering::Release);
805 unsafe { std::ptr::write_volatile(gm, local_mem) };
806
807 // === CHANGE DETECTION & NOTIFICATION ===
808 let changes = local_mem.get_changes(&prev_mem);
809 if !changes.is_empty() {
810 // Construct bulk write message
811 let mut data_map = serde_json::Map::new();
812 for (key, val) in changes {
813 data_map.insert(key.to_string(), val);
814 }
815
816 let msg = CommandMessage::request("gm.write", serde_json::Value::Object(data_map));
817 let msg_json = serde_json::to_string(&msg).unwrap_or_default();
818
819 // Send via the shared write channel (non-blocking)
820 if let Err(e) = ws_write_tx.send(msg_json) {
821 log::error!("Failed to send updates: {}", e);
822 }
823 }
824
825 // Signal Busy/Done event
826 if let Some(ref busy_ev) = busy_event {
827 let _ = busy_ev.set(EventState::Signaled);
828 }
829 }
830
831 Ok(())
832 })
833 }
834
835 fn find_offset(&self, layout: &HashMap<String, serde_json::Value>, name: &str) -> Result<usize> {
836 let info = layout.get(name).ok_or_else(|| anyhow!("Signal '{}' not found in layout", name))?;
837 info.get("offset")
838 .and_then(|v| v.as_u64())
839 .map(|v| v as usize)
840 .ok_or_else(|| anyhow!("Invalid offset for '{}'", name))
841 }
842}
843
844/// Generates the standard `main` function for a control program.
845///
846/// This macro reduces boilerplate by creating a properly configured `main`
847/// function that initializes and runs your control program.
848///
849/// # Arguments
850///
851/// * `$prog_type` - The type of your control program (must implement [`ControlProgram`])
852/// * `$shm_name` - The shared memory segment name (string literal)
853/// * `$tick_signal` - The tick signal name in shared memory (string literal)
854///
855/// # Example
856///
857/// ```ignore
858/// mod gm;
859/// use gm::GlobalMemory;
860///
861/// pub struct MyProgram;
862///
863/// impl MyProgram {
864/// pub fn new() -> Self { Self }
865/// }
866///
867/// impl autocore_std::ControlProgram for MyProgram {
868/// type Memory = GlobalMemory;
869///
870/// fn process_tick(&mut self, ctx: &mut autocore_std::TickContext<Self::Memory>) {
871/// // Your logic here
872/// }
873/// }
874///
875/// // This generates the main function
876/// autocore_std::autocore_main!(MyProgram, "my_project_shm", "tick");
877/// ```
878///
879/// # Generated Code
880///
881/// The macro expands to:
882///
883/// ```ignore
884/// fn main() -> anyhow::Result<()> {
885/// let config = autocore_std::RunnerConfig {
886/// server_host: "127.0.0.1".to_string(),
887/// ws_port: autocore_std::DEFAULT_WS_PORT,
888/// module_name: "control".to_string(),
889/// shm_name: "my_project_shm".to_string(),
890/// tick_signal_name: "tick".to_string(),
891/// busy_signal_name: None,
892/// log_level: log::LevelFilter::Info,
893/// log_udp_port: autocore_std::logger::DEFAULT_LOG_UDP_PORT,
894/// };
895///
896/// autocore_std::ControlRunner::new(MyProgram::new())
897/// .config(config)
898/// .run()
899/// }
900/// ```
901#[macro_export]
902macro_rules! autocore_main {
903 ($prog_type:ty, $shm_name:expr, $tick_signal:expr) => {
904 fn main() -> anyhow::Result<()> {
905 let config = autocore_std::RunnerConfig {
906 server_host: "127.0.0.1".to_string(),
907 ws_port: autocore_std::DEFAULT_WS_PORT,
908 module_name: "control".to_string(),
909 shm_name: $shm_name.to_string(),
910 tick_signal_name: $tick_signal.to_string(),
911 busy_signal_name: None,
912 log_level: log::LevelFilter::Info,
913 log_udp_port: autocore_std::logger::DEFAULT_LOG_UDP_PORT,
914 };
915
916 autocore_std::ControlRunner::new(<$prog_type>::new())
917 .config(config)
918 .run()
919 }
920 };
921}
922