genericArmCtrl.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef __GENERIC_ARM_CTRL_V4_H_
19 #define __GENERIC_ARM_CTRL_V4_H_
20 
21 #include "ros/ros.h"
22 //#include "Manipulation/ManipUtil/Joint.h"
23 //#include "ManipUtil/datastructsManipulator.h"
24 //#include "ManipUtil/ManipulatorXML.h"
25 //#include "Interfaces/KinematicsInterface.h"
26 //#include "Interfaces/armInterface_ctrl.h"
27 
28 #include <trajectory_msgs/JointTrajectory.h>
29 
32 
34 {
35  public:
36 
37  genericArmCtrl(int DOF, double PTPvel = 0.7, double PTPacc = 0.2, double maxError = 0.7);
39 
40  std::vector<double> GetPTPvel() const;
41  std::vector<double> GetPTPacc() const;
42  void SetPTPvel(double vel);
43  void SetPTPacc(double acc);
44 
45  double overlap_time;
46 
47  // void stop(); --> TODO: better reset
48 
49  bool step(std::vector<double> current_pos, std::vector<double> & desired_vel);
50 
51  bool moveThetas(std::vector<double> conf_goal, std::vector<double> conf_current);
52  bool moveTrajectory(trajectory_msgs::JointTrajectory pfad, std::vector<double> conf_current);
53 
54 
55 // bool movePos(AbsPos position);
56 
57  int m_DOF;
58 
60 
61  std::vector<double> m_vel_js;
62  std::vector<double> last_q;
63  std::vector<double> last_q1;
64  std::vector<double> last_q2;
65  std::vector<double> last_q3;
66  std::vector<double> m_acc_js;
67  bool isMoving;
68 
70  double TotalTime_;
71  double m_P;
72  double m_Vorsteuer;
75  double m_TargetError;
76  double m_ExtraTime; // Zusätzliche Zeit, um evtl. verbleibende Regelfehler auszuregeln
77 };
78 
79 
80 
81 #endif
void SetPTPvel(double vel)
double m_TargetError
RefVal_JS * m_pRefVals
std::vector< double > last_q
bool step(std::vector< double > current_pos, std::vector< double > &desired_vel)
bool moveThetas(std::vector< double > conf_goal, std::vector< double > conf_current)
Will move the component to a goal configuration in Joint Space.
std::vector< double > m_vel_js
std::vector< double > m_acc_js
bool moveTrajectory(trajectory_msgs::JointTrajectory pfad, std::vector< double > conf_current)
genericArmCtrl(int DOF, double PTPvel=0.7, double PTPacc=0.2, double maxError=0.7)
double m_CurrentError
std::vector< double > GetPTPacc() const
std::vector< double > last_q2
std::vector< double > GetPTPvel() const
void SetPTPacc(double acc)
std::vector< double > last_q3
TimeStamp startTime_
std::vector< double > last_q1
double m_AllowedError


cob_trajectory_controller
Author(s): Alexander Bubeck
autogenerated on Thu Apr 8 2021 02:39:55