Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Prepare for origin shift 2020 #618

Open
wants to merge 31 commits into
base: master
Choose a base branch
from

Conversation

ashgillman
Copy link
Collaborator

Supersedes #260, I rebased and didn't want to overwrite just yet.

@ashgillman
Copy link
Collaborator Author

Last commit (6da72d8) ties to re-centre the FOV for backwards compatibility, and to make sure the data symmetries test runs. No dice though unforunately, and we fail even more tests.

Before:

      Start  1: test_DataSymmetriesForBins_PET_CartesianGrid

1: Test command: /datasets/scratch/HB_ATLAS_APPS/hb-18-cdc/stir/dev/src/recon_test/test_DataSymmetriesForBins_PET_CartesianGrid
1: Test timeout computed to be: 9.99988e+06
1: Tests for DataSymmetriesForBins_PET_CartesianGrid
1: Testing span=1
1:      Tests with usual image size
1:
1: INFO: Determined voxel size by dividing default_bin_size (3.12932) by zoom
1:              Testing with all symmetries
1:              Testing with all symmetries except 90-phi
1:              Testing with all symmetries except phi symms
1:              Testing with all symmetries except swap_segment
1:              Testing with all symmetries except swap_s
1:              Testing with all symmetries except shift_z
1:              Testing with only shift_z
1:      Tests with shifted origin
1:              Testing with all symmetries
1:              Testing with all symmetries except 90-phi
1:              Testing with all symmetries except phi symms
1:              Testing with all symmetries except swap_segment
1:              Testing with all symmetries except swap_s
1:              Testing with all symmetries except shift_z
1:              Testing with only shift_z
1:      Tests with non-standard range of planes (larger)
1:              Testing with all symmetries
1: Error. comparing lors
1: Current bin:  segment = -5, axial pos 0, view = 0, tangential_pos_num = 0
1: {4, 0, 0}:0.250234    ||
1: {4, 1, 0}:0.500469    ||
1: {4, 2, 0}:0.500469    ||
1: {4, 3, 0}:0.500469    ||
1: {4, 4, 0}:0.500469    ||
1: {4, 5, 0}:0.500469    ||
1: {4, 6, 0}:0.500469    ||
1: {4, 7, 0}:0.500469    ||
1: {4, 8, 0}:0.500469    ||
1: {5, -8, 0}:0.500469    ||
1: {5, -7, 0}:0.500469    ||
1: {5, -6, 0}:0.500469    ||
1: {5, -5, 0}:0.500469    ||
1: {5, -4, 0}:0.500469    ||
1: {5, -3, 0}:0.500469    ||
1: {5, -2, 0}:0.500469    ||
1: {5, -1, 0}:0.500469    ||
1: {5, 0, 0}:0.500469    ||
1: {5, 1, 0}:0.500469    ||
1: {5, 2, 0}:0.500469    ||
1: {5, 3, 0}:0.500469    ||
1: {5, 4, 0}:0.500469    ||
1: {5, 5, 0}:0.500469    ||
1: {5, 6, 0}:0.500469    ||
1: {5, 7, 0}:0.500469    ||
1: {5, 8, 0}:0.500469    ||
1: {6, -8, 0}:0.500469    ||
1: {6, -7, 0}:0.500469    ||
1: {6, -6, 0}:0.500469    ||
1: {6, -5, 0}:0.500469    ||
1: {6, -4, 0}:0.500469    ||
1: {6, -3, 0}:0.500469    ||
1: {6, -2, 0}:0.500469    ||
1: {6, -1, 0}:0.500469    ||
1:                        ||   {6, 1, 0}:0.500469
1:                        ||   {6, 2, 0}:0.500469
1:                        ||   {6, 3, 0}:0.500469
1:                        ||   {6, 4, 0}:0.500469
1:                        ||   {6, 5, 0}:0.500469
1:                        ||   {6, 6, 0}:0.500469
1:                        ||   {6, 7, 0}:0.500469
1:                        ||   {6, 8, 0}:0.500469
1:                        ||   {7, -8, 0}:0.500469
1:                        ||   {7, -7, 0}:0.500469
1:                        ||   {7, -6, 0}:0.500469
1:                        ||   {7, -5, 0}:0.500469

After:

      Start  1: test_DataSymmetriesForBins_PET_CartesianGrid

1: Test command: /datasets/scratch/HB_ATLAS_APPS/hb-18-cdc/stir/dev/src/recon_test/test_DataSymmetriesForBins_PET_CartesianGrid
1: Test timeout computed to be: 9.99988e+06
1: Tests for DataSymmetriesForBins_PET_CartesianGrid
1: Testing span=1
1:      Tests with usual image size
1:
1: INFO: Determined voxel size by dividing default_bin_size (3.12932) by zoom
1:              Testing with all symmetries
1:              Testing with all symmetries except 90-phi
1:              Testing with all symmetries except phi symms
1:              Testing with all symmetries except swap_segment
1:              Testing with all symmetries except swap_s
1:              Testing with all symmetries except shift_z
1:              Testing with only shift_z
1:      Tests with shifted origin
1:              Testing with all symmetries
1: Error. comparing lors
1: Current bin:  segment = -5, axial pos 0, view = 0, tangential_pos_num = 0
1:                        ||   {-2, 0, 0}:0.250235
1:                        ||   {-2, 1, 0}:0.500469
1:                        ||   {-2, 2, 0}:0.500469
1:                        ||   {-2, 3, 0}:0.500469
1:                        ||   {-2, 4, 0}:0.500469
1:                        ||   {-2, 5, 0}:0.500469
1:                        ||   {-2, 6, 0}:0.500469
1:                        ||   {-2, 7, 0}:0.500469
1:                        ||   {-2, 8, 0}:0.500469
1:                        ||   {-1, -8, 0}:0.500469
1:                        ||   {-1, -7, 0}:0.500469
1:                        ||   {-1, -6, 0}:0.500469
1:                        ||   {-1, -5, 0}:0.500469
1:                        ||   {-1, -4, 0}:0.500469
1:                        ||   {-1, -3, 0}:0.500469
1:                        ||   {-1, -2, 0}:0.500469
1:                        ||   {-1, -1, 0}:0.500469
1:                        ||   {-1, 0, 0}:0.500469
1:                        ||   {-1, 1, 0}:0.500469
1:                        ||   {-1, 2, 0}:0.500469
1:                        ||   {-1, 3, 0}:0.500469
1:                        ||   {-1, 4, 0}:0.500469
1:                        ||   {-1, 5, 0}:0.500469
1:                        ||   {-1, 6, 0}:0.500469
1:                        ||   {-1, 7, 0}:0.500469
1:                        ||   {-1, 8, 0}:0.500469
1:                        ||   {0, -8, 0}:0.500469
1:                        ||   {0, -7, 0}:0.500469
1:                        ||   {0, -6, 0}:0.500469
1:                        ||   {0, -5, 0}:0.500469
1:                        ||   {0, -4, 0}:0.500469
1:                        ||   {0, -3, 0}:0.500469
1:                        ||   {0, -2, 0}:0.500469
1:                        ||   {0, -1, 0}:0.500469
1:                        ||   {0, 0, 0}:0.250234
1: {4, 0, 0}:0.250234    ||
1: {4, 1, 0}:0.500469    ||
1: {4, 2, 0}:0.500469    ||
1: {4, 3, 0}:0.500469    ||
1: {4, 4, 0}:0.500469    ||
1: {4, 5, 0}:0.500469    ||
1: {4, 6, 0}:0.500469    ||
1: {4, 7, 0}:0.500469    ||
1: {4, 8, 0}:0.500469    ||
1: {5, -8, 0}:0.500469    ||
1: {5, -7, 0}:0.500469    ||
1: {5, -6, 0}:0.500469    ||
1: {5, -5, 0}:0.500469    ||
1: {5, -4, 0}:0.500469    ||
1: {5, -3, 0}:0.500469    ||
1: {5, -2, 0}:0.500469    ||
1: {5, -1, 0}:0.500469    ||
1: {5, 0, 0}:0.500469    ||
1: {5, 1, 0}:0.500469    ||

So there's an issue with my logic on that realignment I assume.

At least we've now rebased against master and have successfully caught up to before, plus I have made a little progress in being able to actually compile everything with get_physical_coordinates_for_gantry_coordinates() depending on DicretisedDensity.

@ashgillman
Copy link
Collaborator Author

Just posting a link to the last commit attempting to preserve back-compat before I revert, following discussion yesterday that it may not be a significant issue with 5.0 coming up.
ashgillman@6da72d8

@ashgillman ashgillman force-pushed the prepare-for-origin-shift-2020 branch from 6da72d8 to 5b962db Compare July 8, 2020 06:14
@ashgillman
Copy link
Collaborator Author

https://github.com/UCL/STIR/pull/618/files#diff-b4411dfe3254536bd1a46bbe37b4ff0cL106-L113

I'm struggling to make sense of what this is doing (DataSymmetriesForBins_PET_CartesianGrid) and how to modify this to use the ProjDataInfo interface.

    axial_pos_to_z_offset[segment_num] = 
      (cartesian_grid_info_ptr->get_max_index() + cartesian_grid_info_ptr->get_min_index())/2.F
      - cartesian_grid_info_ptr->get_origin().z()/image_plane_spacing
      -
      (num_planes_per_axial_pos[segment_num]
       *(proj_data_info_cyl_ptr->get_max_axial_pos_num(segment_num)  
         + proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num))
       + num_planes_per_scanner_ring*delta)/2;
      (cartesian_grid_info_ptr->get_max_index() + cartesian_grid_info_ptr->get_min_index())/2.F
      - cartesian_grid_info_ptr->get_origin().z()/image_plane_spacing

^ This is easy its the middle of the image in index coordinates

      num_planes_per_axial_pos[segment_num]
       *(proj_data_info_cyl_ptr->get_max_axial_pos_num(segment_num)  
         + proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num))

Here gets tricky. What exactly is axial pos, a virual ring in the micheologram?

So min_axial_pos + max_axial_pos should equal n virtual rings for the whole scanner? (i.e., n_rings for span 0, 2n-1 otherwise?)

image
In this image here, for the sinogram represented by the dot I circled in red (segment +1), is that corresponding to axial position 0 or axial position 4? If the former, the min + max should be constant, but if the latter, the min should always be 0? I can't quite make sense of the logic here.

I assume that last code segment is trying to encode the length of the segment coverage somehow.

       + num_planes_per_scanner_ring*delta

^ This part I'm confused with as well, I'm having troubles working out exactly how I should interpret delta, but I guess this is some sort of offset for the segment

      (num_planes_per_axial_pos[segment_num]
       *(proj_data_info_cyl_ptr->get_max_axial_pos_num(segment_num)  
         + proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num))
       + num_planes_per_scanner_ring*delta)/2;

^ But why are we taking the average of these two? (It is in the format of (A + B)/2))

My goal is to be able to replace this all with a function in ProjDataInfo which will take perhaps a segment, or an LOR in the segment and give a position back in gantry coordinates. In ProjMatrixByBinUsingRatTracing this was ultimately done here: https://github.com/UCL/STIR/pull/618/files#diff-2ee3e081482cf38e475e2fe04089194fR657

ProjDataInfo::get_point_on_lor_in_gantry_coordinates
(const float s_in_mm, const float m_in_mm, const float a_in_mm,
 const float cphi, const float sphi, const float tantheta) const
{
  return CartesianCoordinate3D<float>(m_in_mm      - a_in_mm*tantheta, // z
                                      s_in_mm*sphi - a_in_mm*cphi,     // y
                                      s_in_mm*cphi + a_in_mm*sphi);    // x
}

Which was called by this helper function in ProjMatrixByBinUsingRatTracing:

CartesianCoordinate3D<float>
get_point_on_lor_in_index_coordinates
(const float s_in_mm, const float m_in_mm, const float a_in_mm,
 const float cphi, const float sphi, const float tantheta,
 const DiscretisedDensity<3, float>& density_info,
 const ProjDataInfo& proj_data_info)
{
  return density_info.get_index_coordinates_for_physical_coordinates
    (proj_data_info.get_physical_coordinates_for_gantry_coordinates
     (proj_data_info.get_point_on_lor_in_gantry_coordinates
      (s_in_mm, m_in_mm, a_in_mm, cphi, sphi, tantheta)));
}

@ashgillman
Copy link
Collaborator Author

I should add, the values of the offsets were a little perplexing.

1: INFO: axial_pos_to_z_offset[-5]: 10
1:
1: INFO: axial_pos_to_z_offset[-4]: 8
1:
1: INFO: axial_pos_to_z_offset[-3]: 6
1:
1: INFO: axial_pos_to_z_offset[-2]: 4
1:
1: INFO: axial_pos_to_z_offset[-1]: 2
1:
1: INFO: axial_pos_to_z_offset[0]: 0
1:
1: INFO: axial_pos_to_z_offset[1]: 0
1:
1: INFO: axial_pos_to_z_offset[2]: 0
1:
1: INFO: axial_pos_to_z_offset[3]: 0
1:
1: INFO: axial_pos_to_z_offset[4]: 0
1:
1: INFO: axial_pos_to_z_offset[5]: 0

or

1: INFO: axial_pos_to_z_offset[-5]: 7
1:
1: INFO: axial_pos_to_z_offset[-4]: 5
1:
1: INFO: axial_pos_to_z_offset[-3]: 3
1:
1: INFO: axial_pos_to_z_offset[-2]: 1
1:
1: INFO: axial_pos_to_z_offset[-1]: -1
1:
1: INFO: axial_pos_to_z_offset[0]: -3
1:
1: INFO: axial_pos_to_z_offset[1]: -3
1:
1: INFO: axial_pos_to_z_offset[2]: -3
1:
1: INFO: axial_pos_to_z_offset[3]: -3
1:
1: INFO: axial_pos_to_z_offset[4]: -3
1:
1: INFO: axial_pos_to_z_offset[5]: -3

i.e., constant except for non-negative segments.

@KrisThielemans
Copy link
Collaborator

What exactly is axial pos, a virtual ring in the michelogram

yes. they happen to start from 0, and therefore go to num_axial_poss()-1, but STIR doesn't really rely on that. (3DRP in fact uses other ranges for missing data)

min_axial_pos + max_axial_pos should equal n virtual rings for the whole scanner? (i.e., n_rings for span 0, 2n-1 otherwise?)

min_axial_pos + max_axial_pos + 1, yes. The totals that you quote are ok only for segment 0 of course

I'm having troubles working out exactly how I should interpret delta, but I guess this is some sort of offset for the segment

delta is the average ring difference for the segment.

so, (num_planes_per_axial_pos[segment_num]*axial_pos) + (num_planes_per_scanner_ring*delta) will give you a "plane"-coordinate for the middle of the first LOR,, and then we make an average between the first and last.

Anyway, all to be replaced with get_m() stuff I guess

@ashgillman
Copy link
Collaborator Author

Thanks, I'm still puzzled as to why +/- segments don't have the same z offset though 🤔
That perhaps means get_m won't be appropriate. I suspect it is using the end of the LOR (which would be at the first ring for segment 0+, but if measured the other direction would not be at another ring for negative segments)

@ashgillman
Copy link
Collaborator Author

ashgillman commented Jul 9, 2020

I was thinking today that perhaps symmetries are a sinogram-space thing, and tried replacing:

      (cartesian_grid_info_ptr->get_max_index() + cartesian_grid_info_ptr->get_min_index())/2.F
      - cartesian_grid_info_ptr->get_origin().z()/image_plane_spacing

(i.e., the middle of the image)

with

    const float middle_of_scanner = (num_rings - 1) * num_planes_per_scanner_ring / 2;

(i.e., the middle of the rings)

or

      num_planes_per_axial_pos[0]
       *(proj_data_info_cyl_ptr->get_max_axial_pos_num(0)  
         + proj_data_info_cyl_ptr->get_min_axial_pos_num(0))
        / 2

(i.e., the middle of segment 0)

Which both pass more tests than before, but fail on "z voxel size 2 mtimes larger than usual"

But I think I realise the error in my ways, this really does have to be tied with the real voxel locations as the symmetries are inherantly a voxel-to-lor mapping property.

@ashgillman
Copy link
Collaborator Author

I feel like it should be like this:

    const float middle_of_scanner_in_index_coords_z =
      cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
        proj_data_info_cyl_ptr->get_gantry_isocentre_in_physical_coordinates()
      )[1];

    // ...

    axial_pos_to_z_offset[segment_num] = 
      // (cartesian_grid_info_ptr->get_max_index() + cartesian_grid_info_ptr->get_min_index())/2.F
      // - cartesian_grid_info_ptr->get_origin().z()/image_plane_spacing
      middle_of_scanner_in_index_coords_z
      -
      (num_planes_per_axial_pos[segment_num]
       *(proj_data_info_cyl_ptr->get_max_axial_pos_num(segment_num)  
         + proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num))
       + num_planes_per_scanner_ring*delta)/2;

But I've done something wrong as middle_of_scanner_in_index_coords_z is giving me the end ring, not the middle.

@KrisThielemans
Copy link
Collaborator

The purpose of this code is written here

/*! z = num_planes_per_axial_pos * axial_pos_num + axial_pos_to_z_offset

Sadly, it doesn't say what it means with z. It seems a convention introduced in Matthias Egger's old "on-the-fly" projectors. He had good drawings in his thesis, but I don't have access to that now (could be in my office). Note that this part of the formula works out for span=1 as num_rings-1-abs(delta)+delta.

Interestingly, in

const float transform_z_float = (2*num_planes_per_axial_pos[segment_num]*(axial_pos_num)
+ num_planes_per_scanner_ring*delta
+ 2*axial_pos_to_z_offset[segment_num]);

the puzzling delta term gets added back in again, such that it actually disappears I believe, which makes a tiny bit of sense to me.

In any case, I believe we could reproduce the code as

// KT doubts that the offset code is correct unless the following holds
assert(min_axial_pos_num==0);

Bin first_bin(segment_num, min_axial_pos_num,0,0);
axial_pos_to_z_offset[segment_num] = 
      cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
            proj_data_info_cyl_ptr->get_gantry_isocentre_in_physical_coordinates() +
            CartesianCoordinate3D(get_m(first_bin) -  ring_spacing*delta/2, 0,0)
      )[1];

I think I've got that right, but not sure! By the way, get_m is defined using

m_offset[segment_num] =
((get_max_axial_pos_num(segment_num) + get_min_axial_pos_num(segment_num))
*get_axial_sampling(segment_num)
)/2;

@ashgillman
Copy link
Collaborator Author

Great, I had to slightly modify that to:

          cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
                proj_data_info_cyl_ptr->get_gantry_isocentre_in_physical_coordinates() +
                proj_data_info_cyl_ptr->get_physical_coordinates_for_gantry_coordinates(
                  // CartesianCoordinate3D<float>(proj_data_info_cyl_ptr->get_m(first_bin) - ring_spacing*delta/2, 0,0)
                  CartesianCoordinate3D<float>(
                    proj_data_info_cyl_ptr->get_m(first_bin)
                    - proj_data_info_cyl_ptr->get_axial_sampling(segment_num)*delta/2,
                    0,0)
                )
        )[1];

(convert the CC from gantry to physical, and should be axial sampling, not ring spacing).
I can /almost/ understand why it works..

Doesn't quite solve my problems though, but unfortunately I've had an afternoon disruption and I've had to run away from this 👎 More details to come...

@KrisThielemans
Copy link
Collaborator

I can see the convert, but I don't understand the use of axial_sampling*delta. delta is a ring difference. Why would this formula depend on how much span was used? The original had num_planes_per_scanner_ring*delta.

@ashgillman
Copy link
Collaborator Author

So, using the following I actually match the ProjMatrixByBinUsingRayTracing implementation successfully and all symmetries match and all tests pass:

    const float middle_of_scanner = (num_rings - 1) * proj_data_info_cyl_ptr->get_ring_spacing() / 2;
    axial_pos_to_z_offset[segment_num] = 
          // cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
          //         CartesianCoordinate3D<float>( middle_of_scanner, 0, 0)
          // )[1]
      (middle_of_scanner
      - cartesian_grid_info_ptr->get_origin().z())/image_plane_spacing
      // middle_of_scanner_in_index_coords_z
      -
      (num_planes_per_axial_pos[segment_num]
       *(proj_data_info_cyl_ptr->get_max_axial_pos_num(segment_num)  
         + proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num))
       + num_planes_per_scanner_ring*delta)/2;

So we at least have a working reference implementation. For the first test, this gives an `axial_pos_to_z_offset' vector like: {10, 8, 6, 4, 2, 0, 0, 0, 0, 0, 0}.

Yours:

    axial_pos_to_z_offset[segment_num] = 
          cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
                proj_data_info_cyl_ptr->get_gantry_isocentre_in_physical_coordinates() +
                proj_data_info_cyl_ptr->get_physical_coordinates_for_gantry_coordinates(
                  CartesianCoordinate3D<float>(
                    proj_data_info_cyl_ptr->get_m(first_bin)
                    - ring_spacing*delta/2,
                    0,0)
                )
        )[1];

The problem with your proposed solution is that the ring_spacing * delta / 2 term isn't great enough to balance out the get_m() term in the positive segments, and the resulting offsets aren't integers, so you end up with an `axial_pos_to_z_offset' vector like: {39.4444, 37.5556, 35.6667, 33.7778, 31.8889, 30, 30.1111, 30.2222, 30.3333, 30.4444, 30.5556} (non-integer, and increasing in positive segments).

I realised there's no need to add the gantry isocentre in, this is done by get_physical_coordinates_for_gantry_coordinates():

    axial_pos_to_z_offset[segment_num] = 
          cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
                // proj_data_info_cyl_ptr->get_gantry_isocentre_in_physical_coordinates() +
                proj_data_info_cyl_ptr->get_physical_coordinates_for_gantry_coordinates(
                  CartesianCoordinate3D<float>(
                    proj_data_info_cyl_ptr->get_m(first_bin)
                    - ring_spacing*delta/2,
                    0,0)
                )
        )[1];

{9.44444, 7.55556, 5.66667, 3.77778, 1.88889, 0, 0.111111, 0.222222, 0.333333, 0.444444, 0.555556}
So we've balanced the segment 0 offset to 0 correctly, but still those two issues.

I am not sure why, but for whatever reason it just seems to work better with the axial_sampling instead of ring_spacing. I agree this is not a good reason to use it, we need to work out why but I'm stumped.

    axial_pos_to_z_offset[segment_num] = 
          cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
                proj_data_info_cyl_ptr->get_physical_coordinates_for_gantry_coordinates(
                  CartesianCoordinate3D<float>(
                    proj_data_info_cyl_ptr->get_m(first_bin)
                    - proj_data_info_cyl_ptr->get_axial_sampling(segment_num)*delta/2,
                    0,0)
                )
        )[1];

Gives the correct {10, 8, 6, 4, 2, 0, 0, 0, 0, 0, 0}

I runs through all the tests until it gets to testing span=3 (I assume the others are span=1), and fails here. Obvious evidence that you are right and it should be ring_spacing not axial_sampling as it seems to only work for span=1.

But I'm not sure why these are different for span=1. I naively might have thought that axial sampling and ring spacing would be the same without any compression. Or that it might be a half. But instead, for the initial tests I see ring_spacing=6 and axial sampling = 6.75, whereas in the failing span=3 test ring_spacting=6 and axial sampling = 3.375.

I need to look a little more into exactly what axial sampling is, but any tips as to why they may differ will really help.

Ash

@ashgillman
Copy link
Collaborator Author

🤦
So it turns out if you cast ring spacing to an int, that's not helpful...

Problem solved. New problems.

The FBP3DRP tests fail on your test, as min axial position isn't 0:
3: ERROR: min axial pos num is nonzero: -11

I assume, though, that really we the get_m() offset for axial position 0, whether that's the first Bin or otherwise. So really we don't need to use get_min_axial_position, and should just use 0. I.e., if it is nonzero, we want to use where the 0 would be anyway, right?

i.e.

    // KT doubts that the offset code is correct unless the following holds
    // if (proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num) != 0) {
    //   error(boost::format("min axial pos num is nonzero: %s") % proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num));
    // }

    // Bin first_bin(segment_num, proj_data_info_cyl_ptr->get_min_axial_pos_num(segment_num), 0, 0);
    // get a bin (any bin) at axial position 0
    Bin first_bin(segment_num, 0, 0, 0);
    const float delta = proj_data_info_cyl_ptr->get_average_ring_difference(segment_num);
    const float segment_offset_in_z_gantry_coords = 
      proj_data_info_cyl_ptr->get_m(first_bin) - ring_spacing*delta/2;

    axial_pos_to_z_offset[segment_num] = 
      cartesian_grid_info_ptr->get_index_coordinates_for_physical_coordinates(
        proj_data_info_cyl_ptr->get_physical_coordinates_for_gantry_coordinates(
          CartesianCoordinate3D<float>(segment_offset_in_z_gantry_coords, 0, 0)
        )
      )[1];

@ashgillman
Copy link
Collaborator Author

That certainly seems to pass the tests, but it would be good to add a test to test_DataStmmetriesForBins with a sinogram like this (I have no idea really what it means to have a non-zero minimum axial position). Is there an easy way to construct one? Perhaps easier to incorporate such a test into FBP3DRP with and without symmetries I guess.

@ashgillman
Copy link
Collaborator Author

I ended up testing by making all reconstruction tests do their initial forward projection for reconstruction with symmetries turned off (they they are turned on, the default, for their reconstruction, confirming consistency). This passed including for FBP3DRP, would this be of interest to include in this PR?

@KrisThielemans
Copy link
Collaborator

good news that this works. The 3DRP mod makes sense. It is of course a bit worrying as we are now uncovering a fuzzy convention that axial_pos=0 is the "first one if you didn't do anything funny to the data". Not exactly a scientific definition... Of course, what all this has to boil down to is how to determine the symmetric axial_pos_num (and corresponding image z). It seems to make sense that this has to be mirrored w.r.t. the centre of the gantry. (Note that of the "z-shift symmetry" is on, it just uses the centre of the LOR, as you can shift things around anyway.

It would be good to see how axial_pos_to_z_offset is actually used, but I'm sure that'll be for another day.

It would definitely be good to add an extended range of axial_pos_num to the symmetries test. Remind me to have a look at that...

@KrisThielemans
Copy link
Collaborator

Extending for missing data is here

proj_data_info_with_missing_data_sptr->
set_min_axial_pos_num(new_min_axial_pos_num, segment_num);
proj_data_info_with_missing_data_sptr->
set_max_axial_pos_num(new_max_axial_pos_num, segment_num);

the rmin_rmax stuff is hard, but we can just add some axial_poss at each end.

By the way, there's some more horrible stuff that around here that will need checking

@ashgillman
Copy link
Collaborator Author

ashgillman commented Jul 21, 2020

It is of course a bit worrying as we are now uncovering a fuzzy convention that axial_pos=0 is the "first one if you didn't do anything funny to the data". Not exactly a scientific definition..

I don't think it's necessarily arbitrary, axial_pos=0 should correspond to the location of the first ring, when considering segment 0. I'll have to think of some pithy description to apply to all segments, but I guess its something like "The z offset (in index coordinates) from ring 0 to the start of the first LOR", but the definition of the start of the LOR is a little confusing.

Its a bit unfortunate that axial pos 0 is the first ring, might be simpler if axial pos 0 was the centre of the rings, to be consistent with our new convention that gantry coordinates are zeroed to the centre of the gantry. But that's a lot more work.

@ashgillman
Copy link
Collaborator Author

Hmm, no my definition it seems isn't quite right.. For span > 1 and nonzero segments, the first ring actually corresponds to the end of an LOR at axial pos 1 (not axial pos 0).

Referring back to the michelogram:
image

The issue is that the first and last axial positions here actually correspond to virtual rings slightly outside (by half a ring) the actual end ring.

Another little diagram for a scanner with 5 rings, span 3, looking at segment +1.
image
The outside squares represent detectors and the inside boxes are virtual detectors. You need to end up with an extra virtual detector overhanging the real one to fit the (0, 2) sinogram.

@ashgillman
Copy link
Collaborator Author

Regarding the find_rmin_rmax() code, I'm not convinced that its calculation is actually correct. I think it conservatively overestimates the number of axial positions required.

I managed to convince myself of their core calculation:

  float z_in_image_coordinates =
    -fabs(delta)*num_planes_per_virtual_ring*num_virtual_rings_per_physical_ring*
    (fovrad + proj_data_info_cyl.get_ring_radius())/(2*proj_data_info_cyl.get_ring_radius());

with the following derivation:
image

And I can't see why the following simplification wouldn't hold: (added to the end of the function, with some additional printing.

  info(boost::format("seg: %s : amin: %s, amax: %s")
    % seg_num % proj_data_info_cyl.get_min_axial_pos_num(seg_num) % proj_data_info_cyl.get_max_axial_pos_num(seg_num));
  info(boost::format("seg: %s : rmin: %s, rmax: %s (old)")
    % seg_num % rmin % rmax);

  const float lor_overhang_in_num_rings = fabs(delta) / 2 * (1 + fovrad / proj_data_info_cyl.get_ring_radius());
  const float lor_overhang_in_num_virtual_rings = lor_overhang_in_num_rings * num_virtual_rings_per_physical_ring;
  rmin = static_cast<int>(floor(-lor_overhang_in_num_virtual_rings));
  rmax =  proj_data_info_cyl.get_max_axial_pos_num(seg_num) + (proj_data_info_cyl.get_min_axial_pos_num(seg_num) - rmin);
  info(boost::format("seg: %s : rmin: %s, rmax: %s (alt)")
    % seg_num % rmin % rmax);

This gives the following output for test_FBP3DRP:

3: INFO: seg: -1 : amin: 0, amax: 4
3:
3: INFO: seg: -1 : rmin: -11, rmax: 15 (old)
3:
3: INFO: seg: -1 : rmin: -5, rmax: 9 (alt)
3:
3: INFO: seg: 0 : amin: 0, amax: 8
3:
3: INFO: seg: 0 : rmin: -1, rmax: 9 (old)
3:
3: INFO: seg: 0 : rmin: 0, rmax: 8 (alt)
3:
3: INFO: seg: 1 : amin: 0, amax: 4
3:
3: INFO: seg: 1 : rmin: -5, rmax: 9 (old)
3:
3: INFO: seg: 1 : rmin: -5, rmax: 9 (alt)
3:
3: ================================
3: Reconstruction FBP3DRP finished!
3:
3: Reconstruction diff relative range: [-0.208306, 0.180248]
3: mean abs diff normalised was 0.00707586
3:
3: All tests ok !
3:
3:
1/1 Test #3: test_FBP3DRP .....................   Passed   31.41 sec

NB: That is the identical mean abs diff to previous, so we have the same reconstruction.

So it seems the old implementation overestimated the required additional axial positions for the negative segment (it seems logical that +/- segments should give the same results?)

The differences in segment 0 are because that virtual detector for axial position 0 in segment 0 doesn't quite reach the edge of the ring, see diagram in my last message. Perhaps there needs to be a little more logic to account for the virtual detector placement.

@ashgillman
Copy link
Collaborator Author

Okay, I can see the issue here that this solution does not consider the actual image location at all, it assumes we had an image that starts at the first ring and ends at the last, axially (the transaxial image components are inconsequential).
I think this is okay though. If the actual image FOV is smaller, perhaps you might want to end up with a smaller rmin/rmax to speed up a little bit, but if the image FOV is larger, we don't really want to further extend the rmin/rmax right? You don't really want to actually try to reconstruct any activity outside of the rings with FBP3DRP do you?

@ashgillman
Copy link
Collaborator Author

I've pushed the "don't use symmetries in recon tests" and FBP3DRP rmin/rmax commits, feedback welcome

@ashgillman
Copy link
Collaborator Author

Since I've modified the PMBBURT and none of the other tests are currently failing - does this mean that all other areas of code that assume an image is auto-centred in the gantry are not benchmarked against the main projector? Should we implement failing tests before progressing to the other ORIGINTODO tagged code points? What about the experimental code?

@KrisThielemans
Copy link
Collaborator

I didn't really think we'd go into FBP3DRP corrections here 😉 It does make sense that the numbers of added sinograms would be symmetric of course. I didn't check your proposed formula. I guess you'd have to check what happens when reconstruction a span=1 case as well to see if anything changes.

You don't really want to actually try to reconstruct any activity outside of the rings with FBP3DRP do you?

well... The 3DRP implementation tried to be careful when I gave it motion-corrected proj-data (with LOR-repositioning). As far as I recall, those could be larger than the original scanner, although I cannot immediately find that in the experimental code. I believe I did require that we always added the same number of sinograms at each side, such that the "centre the image" trick still worked. But I wouldn't worry about this probably rather specific case now really. As long as the geometry is fine and the ring are in the right place w.r.t. the image, I won't mind. Let's not try to clean this up too much...

@KrisThielemans
Copy link
Collaborator

Since I've modified the PMBBURT and none of the other tests are currently failing - does this mean that all other areas of code that assume an image is auto-centred in the gantry are not benchmarked against the main projector? Should we implement failing tests before progressing to the other ORIGINTODO tagged code points? What about the experimental code?

hmmm. there's probably no tests comparing projectors.

I think we could retire the on-the-fly ForwardProjectorByBinUsingRayTracing (i.e. the one not using the matrix). When not using multiple-rays, it should give the same results as when using PMBURT. It was there because it used to be a bit faster, but really there's very little point now I believe.

Harder is BackProjectorByBinUsingInterpolation. This is used by 3DRP as it has specific things that think about Jacobian-transformation between spherical and cylindrical coordinates (which you need for an analytic backprojector). That code is very out-of-date though (and has the famous #9 and #11, which is why is recon_test_pack/run_tests.sh --nointbp is used on Travis). Nevertheless, we don't want to tackle that now.

and there's some others as well...

However, I don't really understand what you mean when you that "you've modified PMBURT, so the other tests should fail" (I'm paraphrasing of course)

@ashgillman
Copy link
Collaborator Author

I didn't really think we'd go into FBP3DRP corrections here

I wasn't sure if we should try and address all the "ORIGINTODO" tags in this PR, so that all of STIR's coordinate system definitions remain constant. It seems rather odd to accept this PR, and have the other parts of the code do something different? (Although I'm sure there will inevitably be remaining bugs)

Otherwise, I'm able to revert that commit, pop it in another PR, and we can handle separate elements in separate PRs, then just merge them all around the same time.

However, I don't really understand what you mean when you that "you've modified PMBURT, so the other tests should fail" (I'm paraphrasing of course)

Sorry, it was a bit throwaway. I just mean that I've currently got this branch pointing at a STIR which is internally-inconsistent and half-baked, yet all the tests are passing. It might be a good idea to add some failing tests to make sure we've actually fixed everything when we're done.

@KrisThielemans
Copy link
Collaborator

I didn't really think we'd go into FBP3DRP corrections here

I wasn't sure if we should try and address all the "ORIGINTODO" tags in this PR, so that all of STIR's coordinate system definitions remain constant. It seems rather odd to accept this PR, and have the other parts of the code do something different?

that's not why i meant! I agree we should aim for keeping things consistent. with "FBP3DRP corrections", I meant fixing/changing how many rmin/rmax we have (that should be in a different PR I guess). But if you're confident, I'm happy with it.

I think we'll have to accept that not all projectors are consistent. It's very bad, but very hard to prevent. In fact, the SPECTUB projector isn't compatible with the PET ones. And the NiftyPET projector is almost certainly not compatible either regarding choice of origin (I'd hope the other ones are currently ok).

I just mean that I've currently got this branch pointing at a STIR which is internally-inconsistent and half-baked, yet all the tests are passing. It might be a good idea to add some failing tests to make sure we've actually fixed everything when we're done.

ok. it is definitely a good idea to add tests for new desired behaviour. I wasn't aware you started already on the path of breaking things. In fact, I would have thought that we're aiming for not breaking any tests with "standard" images/data, so the current situation looked good to me.

@KrisThielemans
Copy link
Collaborator

I've reviewed these changes now. I'm happy with the change in ReconstructionTests. great idea. The 3DRP change to find_rmin_rmax is quite reasonable as well, but I feel we need to do this based on (gantry-based) image coordinates. The whole point of this PR is to be able to shift the image around. 3DRP would therefore have missing data in different places than normal. This doesn't seem too hard. Your rmin calculation is for the case where the image is in its standard location, so now we shift it.

// find axial_pos of projection of centre of first plane
CartesianCoordinated3D<float> gantry_coordinates = proj_data_info.get_gantry_coordinates_for_physical(density.get_physical_coordinates(make_coordinate(min_plane,0,0));
float gantry_z = gantry_coordinates .z();
// shift to LOR at edge of image
gantry_z -= lor_overhang_in_num_virtual_rings;
// now go back to axial_pos somehow. maybe like this
float min_axial_pos = (gantry_z - proj_data_info.get_m(Bin(seg,0,0,0))) / proj_dat_info.get_m_spacing(seg);
rmin = static_cast<int>(floor(min_axial_pos));

or something like that.

Once we do that, it seems even easier to just do this with the corners of the image. no longer necessary to compute overhang, i.e. we just can do

proj_data_info.get_gantry_coordinates_for_physical(density.get_physical_coordinates(min_index);

or even better (allowing for x/y offsets) do this with all 4 corners of the first plane. No more thinking, just call some functions...

Also, it seems to me that we need to go between axial_pos and m often, so we need a function for the (gantry_z - proj_data_info.get_m(Bin(seg,0,0,0))) / proj_dat_info.get_m_spacing(seg) calculation (maybe you have one already).

@ashgillman
Copy link
Collaborator Author

The 3DRP change to find_rmin_rmax is quite reasonable as well, but I feel we need to do this based on (gantry-based) image coordinates

Hmm, maybe we can arrange a time for a half-hour chat about this?
I'm just having a hard time understanding exactly why we need this calculation to depend on the density object at all? Does it not make sense to have our "corners" be the FOV radius at the end of the first and last rings? (That's what it was previously anyway, and the current proposal is). If that's the case, I don't see the need to go into image space, in can all be calculated purely in gantry space.

As far as I can tell, the density only had to be accounted for in the previous implementation as the previous definition required all sinogram and image pairs to be centred together. We now only require sinograms to be centred on the gantry, but an image can now be anywhere.

This assumes that the relationship between axial pos and rings is determined completely in gantry space - but I think this should indeed be the case. I made a little diagram earlier today in Powerpoint to convince myself (note my current implementation in FBP3DRP needs to account for the span>1, segment!=0 case). But if this diagram can serve as the definition of axial position 0, then I don't think we need to do any physical space calculations.
image
image

Currently just tests RT matrix fwd and back consistency.
using a different convention called cartesian coordinates, and changed to gantry coordinates
@ashgillman ashgillman force-pushed the prepare-for-origin-shift-2020 branch from de31f09 to 886c95f Compare January 5, 2021 02:28
@ashgillman
Copy link
Collaborator Author

@KrisThielemans Getting close now!

I think all the places needing ticking off are done. I've fixed as many of the tests as I've been able to, including finding a bug in downsample_scanner. I think I'll need some help with the last two:

The ScatterSimulation tests are failing - It seems one of the previously failing tests no longer fails - but I don't think that means I've actually solved the previous problem because the checks still fail.

     Start 12: test_ScatterSimulation                                       
                                                                                                                                                          
12: Test command: /home/gil2a4/build/STIR/src/test/test_ScatterSimulation                                                                                 
12: Test timeout computed to be: 10000000     
12: Error : unequal values are 27 and 31.5. Check the ring spacing.
12: Error : unequal values are 27 and 31.5. Check axial samping. Seg 0                                                                                    
12: Error : unequal values are 27 and 31.5. Check axial samping. Min. Seg                                                                                 
12: Error : unequal values are 27 and 31.5. Check axial samping. Max Seg.
12: Testing scatter simulation for the following scanner:                    
12: Scanner parameters:=                                                                                                                                  
12: Scanner type := ECAT 931                                        
12: Number of rings                          := 8                
12: Number of detectors per ring             := 512                          
12: Inner ring diameter (cm)                 := 102                                                                                                       
12: Average depth of interaction (cm)        := 0.7                                                                                                       
12: Distance between rings (cm)              := 1.35                                                                                                      
12: Default bin size (cm)                    := 0.3129
12: View offset (degrees)                    := 0                                                                                                         
12: Maximum number of non-arc-corrected bins := 192
12: Default number of arc-corrected bins     := 192                                                                                                       
12: Energy resolution := 0.37                                                                                                                             
12: Reference energy (in keV) := 511                                                                                                                      
12: Number of blocks per bucket in transaxial direction         := 4                                                                                      
12: Number of blocks per bucket in axial direction              := 2         
12: Number of crystals per block in axial direction             := 4    
12: Number of crystals per block in transaxial direction        := 8
12: Number of detector layers                                   := 1                                                                                      
12: Number of crystals per singles unit in axial direction      := 4
12: Number of crystals per singles unit in transaxial direction := 32                                                                                     
12: end scanner parameters:=                                                 
12:                                                                                                                          
12: Axial length = 94.5 mm                                       
12:                                                                                                                                                       
12: Setting up for test rings_size14                
12: Starting processing                      
12: Performing checks                                                                                                                                     
12:                                                                                                                                                       
12: Setting up for test rings_size14_def_zoom
12: Starting processing                                                      
12: Performing checks                                                                                                                                     
12:                                                                                                                                                       
12: Setting up for test rings_zoomxy.3_zoomz.4
12: Starting processing                                            
12: Performing checks                                                                                                                                     
12:                                                                                                                                                       
12: Setting up for test rings_size5                                      
12: Starting processing                                                      
12: Performing checks                                                                                                                                     
12:                                                                 
12: Setting up for test rings_zoomz.3                            
12: Starting processing                                                      
12: Performing checks                                                                                                                                     
12:                                                                                                                                                       
12: This test should currently throw an error. You'll see some error messages therefore.                                                                  
12:                                                   
12: Setting up for test act_zoom_rings_zoomxy.3_zoomz.4                                                                                                   
12: Starting processing                            
12: Performing checks                                                                                                                                     
12: Error : unequal values are 170.899 and 180.661. check if symmetric along the scanner axis. test act_zoom_rings_zoomxy.3_zoomz.4                       
12: Error : unequal values are 173.81 and 183.742. check if symmetric along the scanner axis. test act_zoom_rings_zoomxy.3_zoomz.4                        
12: Error : unequal values are 5.46939 and 5.02763. check if symmetric along the tangential_pos direction. test act_zoom_rings_zoomxy.3_zoomz.4           
12: Error. Test on zooming of activity image should have thrown.             
12:                                                                     
12: Setting up for test halfrings_size14                            
12: Starting processing                                                                                                                                   
12: Performing checks                                               
12:                                                                                                                                                       
12: Setting up for test halfrings_size5                                      
12: Starting processing                                                                                                                                   
12: Performing checks                                                        
12:                                                               
12: Setting up for test halfrings_zoomz.3
12: Starting processing                                                    
12: Performing checks                                                                                                                                     
12:    
12: End of tests. Please correct errors !                                  
12:                                                                          
12:                                                                                                                                                       
12/60 Test #12: test_ScatterSimulation ...............................................***Failed   13.74 sec

The zoom_image tests are also failing. Related to #254

test 26                                                                      
      Start 26: test_zoom_image                                                                                                                           
                                                                             
26: Test command: /home/gil2a4/build/STIR/src/test/test_zoom_image                                                                                        
26: Test timeout computed to be: 10000000                                    
26: Tests for zoom_image                                                   
26: Error : Unequal Coordinate value are {30, 40, 50} and {29, 39, 49}. test on multiple argument zoom_image: index range                                 
26:                            
26: End of tests. Please correct errors !                                                                                                                 
26:                                                                          
26:                                                                                                                                                       
26/60 Test #26: test_zoom_image ......................................................***Failed    0.00 sec 

Actually I can't quite work out for myself why my changes have impacted this. I think it crops up around here https://github.com/UCL/STIR/blob/master/src/buildblock/zoom.cxx#L264-L266 in construct_new_image_from_zoom_parameters() and I think is related to the fact the voxel ranges are even. (Or are they? I'm a bit confused between get_lengths and the range)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants