Go to the documentation of this file.00001
00010 #ifndef IMPEDANCE_H
00011 #define IMPEDANCE_H
00012
00013 #include <rtm/idl/BasicDataType.hh>
00014 #include <rtm/idl/ExtendedDataTypes.hh>
00015 #include <rtm/Manager.h>
00016 #include <rtm/DataFlowComponentBase.h>
00017 #include <rtm/CorbaPort.h>
00018 #include <rtm/DataInPort.h>
00019 #include <rtm/DataOutPort.h>
00020 #include <rtm/idl/BasicDataTypeSkel.h>
00021 #include <rtm/idl/ExtendedDataTypesSkel.h>
00022 #include <hrpModel/Body.h>
00023 #include "JointPathEx.h"
00024 #include "RatsMatrix.h"
00025 #include "ImpedanceOutputGenerator.h"
00026
00027
00028 #include "ImpedanceControllerService_impl.h"
00029
00030
00031
00032
00033
00034
00035
00036
00037 using namespace RTC;
00038
00039 class ImpedanceController
00040 : public RTC::DataFlowComponentBase
00041 {
00042 public:
00043 ImpedanceController(RTC::Manager* manager);
00044 virtual ~ImpedanceController();
00045
00046
00047
00048 virtual RTC::ReturnCode_t onInitialize();
00049
00050
00051
00052 virtual RTC::ReturnCode_t onFinalize();
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064 virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00065
00066
00067
00068 virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00069
00070
00071
00072 virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094 bool startImpedanceController(const std::string& i_name_);
00095 bool startImpedanceControllerNoWait(const std::string& i_name_);
00096 bool stopImpedanceController(const std::string& i_name_);
00097 bool stopImpedanceControllerNoWait(const std::string& i_name_);
00098 bool setImpedanceControllerParam(const std::string& i_name_, OpenHRP::ImpedanceControllerService::impedanceParam i_param_);
00099 bool getImpedanceControllerParam(const std::string& i_name_, OpenHRP::ImpedanceControllerService::impedanceParam& i_param_);
00100 void waitImpedanceControllerTransition(std::string i_name_);
00101
00102 protected:
00103
00104
00105
00106
00107
00108
00109
00110 TimedDoubleSeq m_qCurrent;
00111 InPort<TimedDoubleSeq> m_qCurrentIn;
00112 TimedDoubleSeq m_qRef;
00113 InPort<TimedDoubleSeq> m_qRefIn;
00114 TimedPoint3D m_basePos;
00115 InPort<TimedPoint3D> m_basePosIn;
00116 TimedOrientation3D m_baseRpy;
00117 InPort<TimedOrientation3D> m_baseRpyIn;
00118 std::vector<TimedDoubleSeq> m_force;
00119 std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
00120 std::vector<TimedDoubleSeq> m_ref_force;
00121 std::vector<InPort<TimedDoubleSeq> *> m_ref_forceIn;
00122 TimedOrientation3D m_rpy;
00123 InPort<TimedOrientation3D> m_rpyIn;
00124
00125
00126
00127
00128
00129 TimedDoubleSeq m_q;
00130 OutPort<TimedDoubleSeq> m_qOut;
00131
00132
00133
00134
00135
00136 RTC::CorbaPort m_ImpedanceControllerServicePort;
00137
00138
00139
00140
00141
00142 ImpedanceControllerService_impl m_service0;
00143
00144
00145
00146
00147
00148
00149
00150
00151 private:
00152
00153 struct ImpedanceParam : public ImpedanceOutputGenerator {
00154 std::string sensor_name;
00155 hrp::Vector3 ref_force, ref_moment;
00156 double sr_gain, avoid_gain, reference_gain, manipulability_limit;
00157 int transition_count;
00158 hrp::dvector transition_joint_q;
00159 hrp::JointPathExPtr manip;
00160 bool is_active;
00161
00162 ImpedanceParam ()
00163 : ImpedanceOutputGenerator(),
00164 ref_force(hrp::Vector3::Zero()), ref_moment(hrp::Vector3::Zero()),
00165 sr_gain(1.0), avoid_gain(0.001), reference_gain(0.01), manipulability_limit(0.1), transition_count(0), is_active(false)
00166 {};
00167 };
00168 struct ee_trans {
00169 std::string target_name;
00170 hrp::Vector3 localPos;
00171 hrp::Matrix33 localR;
00172 };
00173
00174 void copyImpedanceParam (OpenHRP::ImpedanceControllerService::impedanceParam& i_param_, const ImpedanceParam& param);
00175 void updateRootLinkPosRot (TimedOrientation3D tmprpy);
00176 void getTargetParameters ();
00177 void calcImpedanceControl ();
00178 void calcForceMoment();
00179
00180 std::map<std::string, ImpedanceParam> m_impedance_param;
00181 std::map<std::string, ee_trans> ee_map;
00182 std::map<std::string, hrp::VirtualForceSensorParam> m_vfs;
00183 std::map<std::string, hrp::Vector3> abs_forces, abs_moments, abs_ref_forces, abs_ref_moments;
00184 double m_dt;
00185 hrp::BodyPtr m_robot;
00186 coil::Mutex m_mutex;
00187 hrp::dvector qrefv;
00188 unsigned int m_debugLevel;
00189 int dummy;
00190 int loop;
00191 bool use_sh_base_pos_rpy;
00192 };
00193
00194
00195 extern "C"
00196 {
00197 void ImpedanceControllerInit(RTC::Manager* manager);
00198 };
00199
00200 #endif // IMPEDANCE_H