ublas_types.hpp 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283
  1. /*
  2. * ublas_types.hpp
  3. *
  4. * Created on: Jan 5, 2009
  5. * Author: rubensmits
  6. */
  7. #ifndef UBLAS_TYPES_HPP_
  8. #define UBLAS_TYPES_HPP_
  9. #include <boost/numeric/ublas/matrix.hpp>
  10. #include <boost/numeric/ublas/vector.hpp>
  11. #include <boost/numeric/ublas/matrix_proxy.hpp>
  12. #include <boost/numeric/ublas/vector_proxy.hpp>
  13. #include "kdl/frames.hpp"
  14. #include "kdl/tree.hpp"
  15. #include "kdl/chain.hpp"
  16. #include "kdl/jacobian.hpp"
  17. #include "kdl/jntarray.hpp"
  18. namespace iTaSC{
  19. namespace ublas = boost::numeric::ublas;
  20. using KDL::Twist;
  21. using KDL::Frame;
  22. using KDL::Joint;
  23. using KDL::Inertia;
  24. using KDL::SegmentMap;
  25. using KDL::Tree;
  26. using KDL::JntArray;
  27. using KDL::Jacobian;
  28. using KDL::Segment;
  29. using KDL::Rotation;
  30. using KDL::Vector;
  31. using KDL::Chain;
  32. #define u_scalar double
  33. #define u_vector ublas::vector<u_scalar>
  34. #define u_zero_vector ublas::zero_vector<u_scalar>
  35. #define u_matrix ublas::matrix<u_scalar>
  36. #define u_matrix6 ublas::matrix<u_scalar,6,6>
  37. #define u_identity_matrix ublas::identity_matrix<u_scalar>
  38. #define u_scalar_vector ublas::scalar_vector<u_scalar>
  39. #define u_zero_matrix ublas::zero_matrix<u_scalar>
  40. #define u_vector6 ublas::bounded_vector<u_scalar,6>
  41. inline static int changeBase(const u_matrix& J_in, const Frame& T, u_matrix& J_out) {
  42. if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
  43. return -1;
  44. for (unsigned int j = 0; j < J_in.size2(); ++j) {
  45. ublas::matrix_column<const u_matrix > Jj_in = column(J_in,j);
  46. ublas::matrix_column<u_matrix > Jj_out = column(J_out,j);
  47. Twist arg;
  48. for(unsigned int i=0;i<6;++i)
  49. arg(i)=Jj_in(i);
  50. Twist tmp(T*arg);
  51. for(unsigned int i=0;i<6;++i)
  52. Jj_out(i)=tmp(i);
  53. }
  54. return 0;
  55. }
  56. inline static int changeBase(const ublas::matrix_range<u_matrix >& J_in, const Frame& T, ublas::matrix_range<u_matrix >& J_out) {
  57. if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
  58. return -1;
  59. for (unsigned int j = 0; j < J_in.size2(); ++j) {
  60. ublas::matrix_column<const ublas::matrix_range<u_matrix > > Jj_in = column(J_in,j);
  61. ublas::matrix_column<ublas::matrix_range<u_matrix > > Jj_out = column(J_out,j);
  62. Twist arg;
  63. for(unsigned int i=0;i<6;++i)
  64. arg(i)=Jj_in(i);
  65. Twist tmp(T*arg);
  66. for(unsigned int i=0;i<6;++i)
  67. Jj_out(i)=tmp(i);
  68. }
  69. return 0;
  70. }
  71. }
  72. #endif /* UBLAS_TYPES_HPP_ */