ImpedanceController.h
Go to the documentation of this file.
1 // -*- C++ -*-
10 #ifndef IMPEDANCE_H
11 #define IMPEDANCE_H
12 
13 #include <rtm/idl/BasicDataType.hh>
14 #include <rtm/idl/ExtendedDataTypes.hh>
15 #include <rtm/Manager.h>
16 #include <rtm/DataFlowComponentBase.h>
17 #include <rtm/CorbaPort.h>
18 #include <rtm/DataInPort.h>
19 #include <rtm/DataOutPort.h>
20 #include <rtm/idl/BasicDataTypeSkel.h>
21 #include <rtm/idl/ExtendedDataTypesSkel.h>
22 #include <hrpModel/Body.h>
23 #include "JointPathEx.h"
24 #include "RatsMatrix.h"
26 // Service implementation headers
27 // <rtc-template block="service_impl_h">
29 
30 // </rtc-template>
31 
32 // Service Consumer stub headers
33 // <rtc-template block="consumer_stub_h">
34 
35 // </rtc-template>
36 
37 using namespace RTC;
38 
41 {
42  public:
44  virtual ~ImpedanceController();
45 
46  // The initialize action (on CREATED->ALIVE transition)
47  // formaer rtc_init_entry()
48  virtual RTC::ReturnCode_t onInitialize();
49 
50  // The finalize action (on ALIVE->END transition)
51  // formaer rtc_exiting_entry()
52  virtual RTC::ReturnCode_t onFinalize();
53 
54  // The startup action when ExecutionContext startup
55  // former rtc_starting_entry()
56  // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id);
57 
58  // The shutdown action when ExecutionContext stop
59  // former rtc_stopping_entry()
60  // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id);
61 
62  // The activated action (Active state entry action)
63  // former rtc_active_entry()
64  virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
65 
66  // The deactivated action (Active state exit action)
67  // former rtc_active_exit()
68  virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
69 
70  // The execution action that is invoked periodically
71  // former rtc_active_do()
72  virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
73 
74  // The aborting action when main logic error occurred.
75  // former rtc_aborting_entry()
76  // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id);
77 
78  // The error action in ERROR state
79  // former rtc_error_do()
80  // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id);
81 
82  // The reset action that is invoked resetting
83  // This is same but different the former rtc_init_entry()
84  // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id);
85 
86  // The state update action that is invoked after onExecute() action
87  // no corresponding operation exists in OpenRTm-aist-0.2.0
88  // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id);
89 
90  // The action that is invoked when execution context's rate is changed
91  // no corresponding operation exists in OpenRTm-aist-0.2.0
92  // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id);
93 
94  bool startImpedanceController(const std::string& i_name_);
95  bool startImpedanceControllerNoWait(const std::string& i_name_);
96  bool stopImpedanceController(const std::string& i_name_);
97  bool stopImpedanceControllerNoWait(const std::string& i_name_);
98  bool setImpedanceControllerParam(const std::string& i_name_, OpenHRP::ImpedanceControllerService::impedanceParam i_param_);
99  bool getImpedanceControllerParam(const std::string& i_name_, OpenHRP::ImpedanceControllerService::impedanceParam& i_param_);
100  void waitImpedanceControllerTransition(std::string i_name_);
101 
102  protected:
103  // Configuration variable declaration
104  // <rtc-template block="config_declare">
105 
106  // </rtc-template>
107 
108  // DataInPort declaration
109  // <rtc-template block="inport_declare">
110  TimedDoubleSeq m_qCurrent;
112  TimedDoubleSeq m_qRef;
114  TimedPoint3D m_basePos;
116  TimedOrientation3D m_baseRpy;
118  std::vector<TimedDoubleSeq> m_force;
119  std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
120  std::vector<TimedDoubleSeq> m_ref_force;
121  std::vector<InPort<TimedDoubleSeq> *> m_ref_forceIn;
122  TimedOrientation3D m_rpy;
124 
125  // </rtc-template>
126 
127  // DataOutPort declaration
128  // <rtc-template block="outport_declare">
129  TimedDoubleSeq m_q;
131 
132  // </rtc-template>
133 
134  // CORBA Port declaration
135  // <rtc-template block="corbaport_declare">
137 
138  // </rtc-template>
139 
140  // Service declaration
141  // <rtc-template block="service_declare">
143 
144  // </rtc-template>
145 
146  // Consumer declaration
147  // <rtc-template block="consumer_declare">
148 
149  // </rtc-template>
150 
151  private:
152 
154  std::string sensor_name;
156  double sr_gain, avoid_gain, reference_gain, manipulability_limit;
157  int transition_count; // negative value when initing and positive value when deleting
160  bool is_active;
161 
164  ref_force(hrp::Vector3::Zero()), ref_moment(hrp::Vector3::Zero()),
165  sr_gain(1.0), avoid_gain(0.001), reference_gain(0.01), manipulability_limit(0.1), transition_count(0), is_active(false)
166  {};
167  };
168  struct ee_trans {
169  std::string target_name;
172  };
173 
174  void copyImpedanceParam (OpenHRP::ImpedanceControllerService::impedanceParam& i_param_, const ImpedanceParam& param);
175  void updateRootLinkPosRot (TimedOrientation3D tmprpy);
176  void getTargetParameters ();
177  void calcImpedanceControl ();
178  void calcForceMoment();
179 
180  std::map<std::string, ImpedanceParam> m_impedance_param;
181  std::map<std::string, ee_trans> ee_map;
182  std::map<std::string, hrp::VirtualForceSensorParam> m_vfs;
183  std::map<std::string, hrp::Vector3> abs_forces, abs_moments, abs_ref_forces, abs_ref_moments;
184  double m_dt;
188  unsigned int m_debugLevel;
189  int dummy;
190  int loop;
192 };
193 
194 
195 extern "C"
196 {
198 };
199 
200 #endif // IMPEDANCE_H
ec_id
std::map< std::string, ImpedanceParam > m_impedance_param
TimedOrientation3D m_baseRpy
std::vector< TimedDoubleSeq > m_ref_force
std::map< std::string, hrp::Vector3 > abs_ref_moments
InPort< TimedOrientation3D > m_rpyIn
manager
RTC::CorbaPort m_ImpedanceControllerServicePort
Eigen::VectorXd dvector
InPort< TimedDoubleSeq > m_qRefIn
ImpedanceControllerService_impl m_service0
Eigen::Vector3d Vector3
std::map< std::string, hrp::VirtualForceSensorParam > m_vfs
Eigen::Matrix3d Matrix33
OpenHRP::vector3 Vector3
InPort< TimedPoint3D > m_basePosIn
ExecutionContextHandle_t UniqueId
InPort< TimedDoubleSeq > m_qCurrentIn
std::vector< InPort< TimedDoubleSeq > * > m_forceIn
OutPort< TimedDoubleSeq > m_qOut
TimedOrientation3D m_rpy
std::vector< TimedDoubleSeq > m_force
std::map< std::string, ee_trans > ee_map
InPort< TimedOrientation3D > m_baseRpyIn
std::vector< InPort< TimedDoubleSeq > * > m_ref_forceIn
void ImpedanceControllerInit(RTC::Manager *manager)


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:50