kinematics6M180.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2008 by Neuronics AG *
3  * support@neuronics.ch *
4  ***************************************************************************/
5 
10 #ifndef _KINEMATICS6M180_H_
11 #define _KINEMATICS6M180_H_
12 
13 //std:
14 #include <string>
15 #include <queue>
16 #include <vector>
17 #include <map>
18 //kinematics:
19 #include "kinematics.h"
21 #include "MathHelperFunctions.h"
22 
23 namespace AnaGuess {
24 
26 
30 class Kinematics6M180 : public Kinematics {
31 private:
37  std::vector<double> mSegmentLength;
39  std::vector<double> mAngleOffset;
41  std::vector<double> mAngleStop;
43  std::vector<int> mEncodersPerCycle;
45  std::vector<int> mEncoderOffset;
47  std::vector<int> mRotationDirection;
50 
52  struct position {
53  double x;
54  double y;
55  double z;
56  };
57  struct angles_calc {
58  double theta1;
59  double theta2;
60  double theta3;
61  double theta4;
62  double theta5;
63  double theta234;
64  double b1;
65  double b2;
66  double costh3;
67  };
68  typedef std::vector<angles_calc> angles_container;
69  static const int cNrOfPossibleSolutions = 8;
70 
72  bool initialize();
73 
75  void IK_b1b2costh3_6M180(angles_calc &a, const position &p) const;
76  void thetacomp(angles_calc &a, const position &p_m) const;
77  bool angledef(angles_calc &a) const;
78  bool AnglePositionTest(const angles_calc &a) const;
79  bool PositionTest6M180(const angles_calc &a, const position &p) const;
80 
81 
82 protected:
83 
84 
85 public:
88 
91 
93  std::vector<double> getLinkLength();
95  std::vector<int> getEpc();
97  std::vector<int> getEncOff();
99  std::vector<int> getDir();
101  std::vector<double> getAngOff();
103  std::vector<double> getAngStop();
105  std::vector<double> getAngRange();
107  std::vector<double> getAngMin();
109  std::vector<double> getAngMax();
111  bool setLinkLength(const std::vector<double> aLengths);
113  bool setAngOff(const std::vector<double> aAngOff);
115  bool setAngStop(const std::vector<double> aAngStop);
116 
121  bool enc2rad(std::vector<double>& aAngles, const std::vector<int> aEncoders);
122 
127  bool rad2enc(std::vector<int>& aEncoders, const std::vector<double> aAngles);
128 
133  bool directKinematics(std::vector<double>& aPosition, const std::vector<double> aAngles);
134 
141  bool inverseKinematics(std::vector<double>& aAngles, const std::vector<double> aPosition, const std::vector<double> aStartingAngles);
142 };
144 
145 } // namespace
146 
147 #endif //_KINEMATICS6M180_H_
bool enc2rad(std::vector< double > &aAngles, const std::vector< int > aEncoders)
std::vector< int > mEncodersPerCycle
Encoders per cycle vector.
int mNumberOfSegments
Number of segments of the robot.
void IK_b1b2costh3_6M180(angles_calc &a, const position &p) const
helper functions
bool directKinematics(std::vector< double > &aPosition, const std::vector< double > aAngles)
std::vector< int > getDir()
get direction
std::vector< int > mRotationDirection
Rotation direction vector [1|-1].
bool setAngOff(const std::vector< double > aAngOff)
set angle offset
Implements the kinematics for the Katana6M180.
std::vector< double > mSegmentLength
Effector segment lengths vector [m].
std::vector< int > getEncOff()
get encoder offset
static const int cNrOfPossibleSolutions
std::vector< int > getEpc()
get encoders per cycle
std::vector< angles_calc > angles_container
std::vector< double > getLinkLength()
get link length
Base Class for the kinematics implementations.
std::vector< double > getAngRange()
get angle range
void thetacomp(angles_calc &a, const position &p_m) const
std::vector< double > mAngleStop
Angle stop vector [rad].
bool PositionTest6M180(const angles_calc &a, const position &p) const
bool setAngStop(const std::vector< double > aAngStop)
set angle stop
std::vector< double > getAngMin()
get angle min
std::vector< double > getAngMax()
get angle max
bool rad2enc(std::vector< int > &aEncoders, const std::vector< double > aAngles)
FloatVector FloatVector * a
std::vector< double > getAngStop()
get angle stop
bool setLinkLength(const std::vector< double > aLengths)
set link length
std::vector< int > mEncoderOffset
Encoder offset vector.
int mNumberOfMotors
Number of motors of the robot.
std::vector< double > mAngleOffset
Angle offset vector [rad].
bool AnglePositionTest(const angles_calc &a) const
structs, type and constants used in inverse kinematics calculation
bool initialize()
initialization routine
bool mIsInitialized
Initialized flag.
std::vector< double > getAngOff()
get angle offset
bool angledef(angles_calc &a) const
bool inverseKinematics(std::vector< double > &aAngles, const std::vector< double > aPosition, const std::vector< double > aStartingAngles)


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44