AUV-Coop-Assembly
Master Thesis for Robotics Engineering. Cooperative peg-in-hole assembly with two underwater vehicles guided by vision
graspConstrainer.h
1 #ifndef GRASPCONSTRAINER_H
2 #define GRASPCONSTRAINER_H
3 
4 #include <Eigen/Core>
5 #include <cmat/cmat.h>
6 
7 #include "../../support/header/defines.h"
8 #include "../../support/header/conversions.h"
9 
10 
24 {
25 
26 public:
27 
34  static std::vector<double> calculateGraspVelocities_arm(
35  Eigen::Matrix<double, 6, ARM_DOF> w_J_man,
36  Eigen::Matrix4d otherEE_T_EE);
37 
45  static std::vector<double> calculateGraspVelocities_armVeh(
46  Eigen::Matrix<double, 6, TOT_DOF> w_Jee_robot,
47  Eigen::Matrix4d wTotherPeg, Eigen::Matrix4d wTee);
48 // static std::vector<double> calculateGraspVelocities_armVeh(
49 // Eigen::Matrix<double, 6, TOT_DOF> w_Jee_robot,
50 // Eigen::Matrix4d otherEE_T_EE);
51 
52 
53 private :
55 };
56 
57 #endif // GRASPCONSTRAINER_H
The GraspConstrainer class.
static std::vector< double > calculateGraspVelocities_armVeh(Eigen::Matrix< double, 6, TOT_DOF > w_Jee_robot, Eigen::Matrix4d wTotherPeg, Eigen::Matrix4d wTee)
calculateGraspVelocities_armVeh for effect of firm grasp on the arm and on the vehicle ...
static std::vector< double > calculateGraspVelocities_arm(Eigen::Matrix< double, 6, ARM_DOF > w_J_man, Eigen::Matrix4d otherEE_T_EE)
calculateGraspVelocities_arm for effect of firm grasp only on the arm