use std::{
collections::HashMap,
sync::{Arc, Mutex},
};
use faer::{Col, Mat};
use rayon::prelude::*;
use crate::error::ErrorLogging;
use crate::linearizer::{LinearizerError, LinearizerResult};
use super::super::linearize_block;
use crate::core::problem::{Problem, VariableEnum};
pub fn assemble_dense(
problem: &Problem,
variables: &HashMap<String, VariableEnum>,
variable_index_map: &HashMap<String, usize>,
total_dof: usize,
) -> LinearizerResult<(Mat<f64>, Mat<f64>)> {
let total_residual = Arc::new(Mutex::new(Col::<f64>::zeros(
problem.total_residual_dimension,
)));
let jacobian_dense = Arc::new(Mutex::new(Mat::<f64>::zeros(
problem.total_residual_dimension,
total_dof,
)));
problem.residual_blocks().par_iter().try_for_each(
|(_, residual_block)| -> Result<(), LinearizerError> {
let block = linearize_block(residual_block, variables, &total_residual)?;
let mut jac_dense = jacobian_dense.lock().map_err(|e| {
LinearizerError::ParallelComputation(
"Failed to acquire lock on dense Jacobian".to_string(),
)
.log_with_source(e)
})?;
for (i, var_key) in residual_block.variable_key_list.iter().enumerate() {
let col_offset = *variable_index_map.get(var_key).ok_or_else(|| {
LinearizerError::Variable(format!(
"Missing key {} in variable-to-column-index mapping",
var_key
))
.log()
})?;
let (variable_local_idx, var_size) = block.variable_local_idx_size_list[i];
let variable_jac = block
.jacobian
.view((0, variable_local_idx), (block.residual_dim, var_size));
for row in 0..block.residual_dim {
for col in 0..var_size {
jac_dense[(block.residual_row_start_idx + row, col_offset + col)] =
variable_jac[(row, col)];
}
}
}
Ok(())
},
)?;
let total_residual = Arc::try_unwrap(total_residual)
.map_err(|_| {
LinearizerError::ParallelComputation(
"Failed to unwrap Arc for total residual".to_string(),
)
.log()
})?
.into_inner()
.map_err(|e| {
LinearizerError::ParallelComputation(
"Failed to extract mutex inner value for total residual".to_string(),
)
.log_with_source(e)
})?;
let jacobian_dense = Arc::try_unwrap(jacobian_dense)
.map_err(|_| {
LinearizerError::ParallelComputation(
"Failed to unwrap Arc for dense Jacobian".to_string(),
)
.log()
})?
.into_inner()
.map_err(|e| {
LinearizerError::ParallelComputation(
"Failed to extract mutex inner value for dense Jacobian".to_string(),
)
.log_with_source(e)
})?;
let residual_faer = total_residual.as_ref().as_mat().to_owned();
Ok((residual_faer, jacobian_dense))
}
#[cfg(test)]
mod tests {
use super::*;
use crate::{core::problem::Problem, factors, linalg::JacobianMode, optimizer};
use apex_manifolds::ManifoldType;
use nalgebra::{DMatrix, DVector, dvector};
use std::collections::HashMap;
type TestResult = Result<(), Box<dyn std::error::Error>>;
struct LinearFactor {
target: f64,
}
impl factors::Factor for LinearFactor {
fn linearize(
&self,
params: &[DVector<f64>],
compute_jacobian: bool,
) -> (DVector<f64>, Option<DMatrix<f64>>) {
let residual = dvector![params[0][0] - self.target];
let jacobian = if compute_jacobian {
Some(DMatrix::from_element(1, 1, 1.0))
} else {
None
};
(residual, jacobian)
}
fn get_dimension(&self) -> usize {
1
}
}
fn one_var_dense_problem() -> (Problem, HashMap<String, (ManifoldType, DVector<f64>)>) {
let mut problem = Problem::new(JacobianMode::Dense);
problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 0.0 }), None);
let mut init = HashMap::new();
init.insert("x".to_string(), (ManifoldType::RN, dvector![5.0]));
(problem, init)
}
#[test]
fn test_assemble_dense_basic() -> TestResult {
let (problem, init) = one_var_dense_problem();
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, jacobian) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert!((residual[(0, 0)] - 5.0).abs() < 1e-12);
assert!((jacobian[(0, 0)] - 1.0).abs() < 1e-12);
Ok(())
}
#[test]
fn test_assemble_dense_jacobian_dimensions() -> TestResult {
let (problem, init) = one_var_dense_problem();
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, jacobian) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert_eq!(residual.nrows(), problem.total_residual_dimension);
assert_eq!(jacobian.nrows(), problem.total_residual_dimension);
assert_eq!(jacobian.ncols(), state.total_dof);
Ok(())
}
#[test]
fn test_assemble_dense_zero_residual() -> TestResult {
let mut problem = Problem::new(JacobianMode::Dense);
problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 3.0 }), None);
let mut init = HashMap::new();
init.insert("x".to_string(), (ManifoldType::RN, dvector![3.0]));
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, _) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert!(residual[(0, 0)].abs() < 1e-12);
Ok(())
}
#[test]
fn test_assemble_dense_two_variables() -> TestResult {
let mut problem = Problem::new(JacobianMode::Dense);
problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 0.0 }), None);
problem.add_residual_block(&["y"], Box::new(LinearFactor { target: 0.0 }), None);
let mut init = HashMap::new();
init.insert("x".to_string(), (ManifoldType::RN, dvector![2.0]));
init.insert("y".to_string(), (ManifoldType::RN, dvector![7.0]));
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, jacobian) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert_eq!(jacobian.nrows(), 2);
assert_eq!(jacobian.ncols(), 2);
let rsum = residual[(0, 0)].abs() + residual[(1, 0)].abs();
assert!((rsum - 9.0).abs() < 1e-12);
Ok(())
}
#[test]
fn test_assemble_dense_residual_faer_shape() -> TestResult {
let (problem, init) = one_var_dense_problem();
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, _) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert_eq!(residual.nrows(), 1);
assert_eq!(residual.ncols(), 1);
Ok(())
}
struct BinaryLinearFactor {
target_x: f64,
target_y: f64,
}
impl factors::Factor for BinaryLinearFactor {
fn linearize(
&self,
params: &[DVector<f64>],
compute_jacobian: bool,
) -> (DVector<f64>, Option<DMatrix<f64>>) {
let residual =
nalgebra::dvector![params[0][0] - self.target_x, params[1][0] - self.target_y];
let jacobian = if compute_jacobian {
let mut j = DMatrix::zeros(2, 2);
j[(0, 0)] = 1.0;
j[(1, 1)] = 1.0;
Some(j)
} else {
None
};
(residual, jacobian)
}
fn get_dimension(&self) -> usize {
2
}
}
#[test]
fn test_assemble_dense_binary_factor() -> TestResult {
let mut problem = Problem::new(JacobianMode::Dense);
problem.add_residual_block(
&["x", "y"],
Box::new(BinaryLinearFactor {
target_x: 0.0,
target_y: 0.0,
}),
None,
);
let mut init = HashMap::new();
init.insert("x".to_string(), (ManifoldType::RN, nalgebra::dvector![3.0]));
init.insert("y".to_string(), (ManifoldType::RN, nalgebra::dvector![5.0]));
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, jacobian) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert_eq!(residual.nrows(), 2);
assert_eq!(jacobian.nrows(), 2);
assert_eq!(jacobian.ncols(), 2);
let r_sum = residual[(0, 0)].abs() + residual[(1, 0)].abs();
assert!((r_sum - 8.0).abs() < 1e-10, "residual sum = {r_sum}");
let jac_sum: f64 = (0..2)
.map(|c| (0..2).map(|r| jacobian[(r, c)]).sum::<f64>())
.sum();
assert!(
(jac_sum - 2.0).abs() < 1e-10,
"sum of jacobian entries = {jac_sum}"
);
Ok(())
}
#[test]
fn test_assemble_dense_missing_variable_key_returns_error() -> TestResult {
let (problem, init) = one_var_dense_problem();
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let empty_map: HashMap<String, usize> = HashMap::new();
let result = assemble_dense(&problem, &state.variables, &empty_map, state.total_dof);
assert!(
result.is_err(),
"missing variable key should produce an Err"
);
Ok(())
}
#[test]
fn test_assemble_dense_multi_block_residual_values() -> TestResult {
let mut problem = Problem::new(JacobianMode::Dense);
problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 1.0 }), None);
problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 4.0 }), None);
let mut init = HashMap::new();
init.insert("x".to_string(), (ManifoldType::RN, dvector![3.0]));
let state = optimizer::initialize_optimization_state(&problem, &init)?;
let (residual, jacobian) = assemble_dense(
&problem,
&state.variables,
&state.variable_index_map,
state.total_dof,
)?;
assert_eq!(residual.nrows(), 2);
let vals: std::collections::HashSet<i64> =
(0..2).map(|i| (residual[(i, 0)] * 1e6) as i64).collect();
assert!(vals.contains(&2_000_000), "Missing residual entry 2.0");
assert!(vals.contains(&-1_000_000), "Missing residual entry -1.0");
assert!((jacobian[(0, 0)] - 1.0).abs() < 1e-10);
assert!((jacobian[(1, 0)] - 1.0).abs() < 1e-10);
Ok(())
}
}