SpaSolver.cpp 2.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  1. /*
  2. * Copyright 2010 SRI International
  3. *
  4. * This program is free software: you can redistribute it and/or modify
  5. * it under the terms of the GNU Lesser General Public License as published by
  6. * the Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This program is distributed in the hope that it will be useful,
  10. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. * GNU Lesser General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU Lesser General Public License
  15. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include "SpaSolver.h"
  18. #include <open_karto/Karto.h>
  19. SpaSolver::SpaSolver()
  20. {
  21. }
  22. SpaSolver::~SpaSolver()
  23. {
  24. }
  25. void SpaSolver::Clear()
  26. {
  27. corrections.clear();
  28. }
  29. const karto::ScanSolver::IdPoseVector& SpaSolver::GetCorrections() const
  30. {
  31. return corrections;
  32. }
  33. void SpaSolver::Compute()
  34. {
  35. corrections.clear();
  36. typedef std::vector<sba::Node2d, Eigen::aligned_allocator<sba::Node2d> > NodeVector;
  37. printf("DO SPA BEGIN\n");
  38. m_Spa.doSPA(40);
  39. printf("DO SPA END\n");
  40. NodeVector nodes = m_Spa.getNodes();
  41. forEach(NodeVector, &nodes)
  42. {
  43. karto::Pose2 pose(iter->trans(0), iter->trans(1), iter->arot);
  44. corrections.push_back(std::make_pair(iter->nodeId, pose));
  45. }
  46. }
  47. void SpaSolver::AddNode(karto::Vertex<karto::LocalizedRangeScan>* pVertex)
  48. {
  49. karto::Pose2 pose = pVertex->GetObject()->GetCorrectedPose();
  50. Eigen::Vector3d vector(pose.GetX(), pose.GetY(), pose.GetHeading());
  51. m_Spa.addNode(vector, pVertex->GetObject()->GetUniqueId());
  52. }
  53. void SpaSolver::AddConstraint(karto::Edge<karto::LocalizedRangeScan>* pEdge)
  54. {
  55. karto::LocalizedRangeScan* pSource = pEdge->GetSource()->GetObject();
  56. karto::LocalizedRangeScan* pTarget = pEdge->GetTarget()->GetObject();
  57. karto::LinkInfo* pLinkInfo = (karto::LinkInfo*)(pEdge->GetLabel());
  58. karto::Pose2 diff = pLinkInfo->GetPoseDifference();
  59. Eigen::Vector3d mean(diff.GetX(), diff.GetY(), diff.GetHeading());
  60. karto::Matrix3 precisionMatrix = pLinkInfo->GetCovariance().Inverse();
  61. Eigen::Matrix<double,3,3> m;
  62. m(0,0) = precisionMatrix(0,0);
  63. m(0,1) = m(1,0) = precisionMatrix(0,1);
  64. m(0,2) = m(2,0) = precisionMatrix(0,2);
  65. m(1,1) = precisionMatrix(1,1);
  66. m(1,2) = m(2,1) = precisionMatrix(1,2);
  67. m(2,2) = precisionMatrix(2,2);
  68. m_Spa.addConstraint(pSource->GetUniqueId(), pTarget->GetUniqueId(), mean, m);
  69. }