GrlVFController.hpp
Go to the documentation of this file.
1 /// @author Andrew Hundt <athundt@gmail.com>
2 
3 #ifndef _GRL_VF_CONTROLLER_
4 #define _GRL_VF_CONTROLLER_
5 
6 #include <tuple>
7 #include <string>
8 #include <sawConstraintController/mtsVFController.h>
9 #include <sawConstraintController/mtsVFDataJointLimits.h>
10 
11 namespace grl {
12 
13 /// create the data object and put the data inside
14 /// @todo move to own header with no vrep dependencies
15 /// @todo figure out how the interface for following the motion will work
16 /// VFControlller stands for "virtual fixtures" controller
17 struct InverseKinematicsController : public mtsVFController {
18 public:
19  typedef mtsVFController parent_type;
20 
30  };
31 
32  typedef std::tuple<
33  std::string // currentKinematicsName
34  ,std::string // desiredKinematicsName
35  ,std::string // followVFName
36  ,std::size_t // followVFNumRows
37  ,std::string // jointVelocityLimitsVFName
38  ,std::size_t // JointVelocityLimitsVFNumRows
39  ,std::string // JointPositionVFName
40  ,std::size_t // JointPositionNumRows
41  > Params;
42 
43 
44  /// @todo maybe parameterize this somehow
45  static const std::size_t totalRows = 7;
46 
47  /// @todo this is just done quickly, make it and the constructor be done right
48  InverseKinematicsController(size_t num_joints, mtsVFBase::CONTROLLERMODE cm):
49  mtsVFController(num_joints,cm) // parent
50  ,currentKinematicsStateP_(new prmKinematicsState())
51  ,desiredKinematicsStateP_(new prmKinematicsState())
52  ,followVFP_(new mtsVFDataBase())
53  ,jointVelocityLimitsVFP_(new mtsVFDataJointLimits())
54  ,jointPositionLimitsVFP_(new mtsVFDataJointLimits())
55  {
56 
57  }
58 
60  {
61 
62  }
63 
65  {
66 
67  }
68 
69  void construct(){
70  }
71 
72  /// This will hold the Jacobian
73  std::unique_ptr<prmKinematicsState> currentKinematicsStateP_;
74 
75  /// This will hold the xyz position and the rotation of where I want to go
76  std::unique_ptr<prmKinematicsState> desiredKinematicsStateP_;
77 
78  // want to follow a goal position
79  /// @todo will want to use an addVFFollow member function once it is added in
80  std::unique_ptr<mtsVFDataBase> followVFP_;
81 
82  /// need velocity limits for the joints
83  std::unique_ptr<mtsVFDataJointLimits> jointVelocityLimitsVFP_;
84  /// joints cannot go to certain position
85  std::unique_ptr<mtsVFDataJointLimits> jointPositionLimitsVFP_;
86 
87 
88 };
89 
90 } // namespace grl
91 
92 #endif
static const std::size_t totalRows
InverseKinematicsController(size_t num_joints, mtsVFBase::CONTROLLERMODE cm)
std::unique_ptr< mtsVFDataJointLimits > jointPositionLimitsVFP_
joints cannot go to certain position
std::tuple< std::string,std::string,std::string,std::size_t,std::string,std::size_t,std::string,std::size_t > Params
std::unique_ptr< prmKinematicsState > desiredKinematicsStateP_
This will hold the xyz position and the rotation of where I want to go.
std::unique_ptr< mtsVFDataJointLimits > jointVelocityLimitsVFP_
need velocity limits for the joints
std::unique_ptr< mtsVFDataBase > followVFP_
std::unique_ptr< prmKinematicsState > currentKinematicsStateP_
This will hold the Jacobian.