ObjectContactTurnaroundDetector.h
Go to the documentation of this file.
1 // -*- C++ -*-
10 #ifndef OBJECTCONTACTTURNAROUNDDETECTOR_H
11 #define OBJECTCONTACTTURNAROUNDDETECTOR_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 <hrpUtil/Eigen3d.h>
23 #include <hrpModel/Body.h>
25 // Service implementation headers
26 // <rtc-template block="service_impl_h">
28 
29 // </rtc-template>
30 
31 // Service Consumer stub headers
32 // <rtc-template block="consumer_stub_h">
33 
34 // </rtc-template>
35 
36 using namespace RTC;
37 
40 {
41  public:
44 
45  // The initialize action (on CREATED->ALIVE transition)
46  // formaer rtc_init_entry()
47  virtual RTC::ReturnCode_t onInitialize();
48 
49  // The finalize action (on ALIVE->END transition)
50  // formaer rtc_exiting_entry()
51  virtual RTC::ReturnCode_t onFinalize();
52 
53  // The startup action when ExecutionContext startup
54  // former rtc_starting_entry()
55  // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id);
56 
57  // The shutdown action when ExecutionContext stop
58  // former rtc_stopping_entry()
59  // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id);
60 
61  // The activated action (Active state entry action)
62  // former rtc_active_entry()
63  virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
64 
65  // The deactivated action (Active state exit action)
66  // former rtc_active_exit()
67  virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
68 
69  // The execution action that is invoked periodically
70  // former rtc_active_do()
71  virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
72 
73  // The aborting action when main logic error occurred.
74  // former rtc_aborting_entry()
75  // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id);
76 
77  // The error action in ERROR state
78  // former rtc_error_do()
79  // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id);
80 
81  // The reset action that is invoked resetting
82  // This is same but different the former rtc_init_entry()
83  // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id);
84 
85  // The state update action that is invoked after onExecute() action
86  // no corresponding operation exists in OpenRTm-aist-0.2.0
87  // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id);
88 
89  // The action that is invoked when execution context's rate is changed
90  // no corresponding operation exists in OpenRTm-aist-0.2.0
91  // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id);
92 
93  void startObjectContactTurnaroundDetection(const double i_ref_diff_wrench, const double i_max_time, const OpenHRP::ObjectContactTurnaroundDetectorService::StrSequence& i_ee_names);
94  OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode checkObjectContactTurnaroundDetection();
95  bool setObjectContactTurnaroundDetectorParam(const OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam &i_param_);
96  bool getObjectContactTurnaroundDetectorParam(OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam& i_param_);
97  bool getObjectForcesMoments(OpenHRP::ObjectContactTurnaroundDetectorService::Dbl3Sequence_out o_forces, OpenHRP::ObjectContactTurnaroundDetectorService::Dbl3Sequence_out o_moments, OpenHRP::ObjectContactTurnaroundDetectorService::DblSequence3_out o_3dofwrench, double& o_fric_coeff_wrench);
98  bool checkObjectContactTurnaroundDetectionForGeneralizedWrench(OpenHRP::ObjectContactTurnaroundDetectorService::DetectorModeSequence_out o_dms);
99  bool startObjectContactTurnaroundDetectionForGeneralizedWrench();
100  bool getObjectGeneralizedConstraintWrenches(OpenHRP::ObjectContactTurnaroundDetectorService::objectGeneralizedConstraintWrenchesParam& o_param);
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  std::vector<TimedDoubleSeq> m_force;
113  std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
114  TimedOrientation3D m_rpy;
116  TimedBooleanSeq m_contactStates;
118 
119  // </rtc-template>
120 
121  // DataOutPort declaration
122  // <rtc-template block="outport_declare">
123  TimedDoubleSeq m_octdData;
125 
126  // </rtc-template>
127 
128  // CORBA Port declaration
129  // <rtc-template block="corbaport_declare">
131 
132  // </rtc-template>
133 
134  // Service declaration
135  // <rtc-template block="service_declare">
137 
138  // </rtc-template>
139 
140  // Consumer declaration
141  // <rtc-template block="consumer_declare">
142 
143  // </rtc-template>
144 
145  private:
146 
147  struct ee_trans {
148  std::string target_name, sensor_name;
151  size_t index;
152  };
153 
154  void updateRootLinkPosRot (TimedOrientation3D tmprpy);
155  void calcFootMidCoords (hrp::Vector3& new_foot_mid_pos, hrp::Matrix33& new_foot_mid_rot);
156  void calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot);
157  void calcObjectContactTurnaroundDetectorState();
158  OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode checkObjectContactTurnaroundDetectionCommon(const size_t index);
159  std::string getEENameFromSensorName (const std::string& sensor_name)
160  {
161  std::string tmp_ee_name("");
162  for (std::map<std::string, ee_trans>::const_iterator it = ee_map.begin(); it != ee_map.end(); it++) if (it->second.sensor_name == sensor_name) tmp_ee_name = it->first;
163  return tmp_ee_name;
164  };
165 
166  std::map<std::string, ee_trans> ee_map;
168  std::vector<std::string> octd_sensor_names;
170  double m_dt;
173  unsigned int m_debugLevel;
174  int dummy;
175  int loop;
176 };
177 
178 
179 extern "C"
180 {
182 };
183 
184 #endif // OBJECTCONTACTTURNAROUNDDETECTOR_H
ec_id
boost::shared_ptr< ObjectContactTurnaroundDetectorBase > octd
manager
Eigen::Vector3d Vector3
Eigen::Matrix3d Matrix33
ExecutionContextHandle_t UniqueId
std::string getEENameFromSensorName(const std::string &sensor_name)
ObjectContactTurnaroundDetectorService_impl m_service0
std::vector< InPort< TimedDoubleSeq > * > m_forceIn
std::map< std::string, ee_trans > ee_map
void ObjectContactTurnaroundDetectorInit(RTC::Manager *manager)


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