#include <ObjectContactTurnaroundDetector.h>

Classes | |
| struct | ee_trans |
Public Member Functions | |
| OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode | checkObjectContactTurnaroundDetection () |
| bool | checkObjectContactTurnaroundDetectionForGeneralizedWrench (OpenHRP::ObjectContactTurnaroundDetectorService::DetectorModeSequence_out o_dms) |
| bool | getObjectContactTurnaroundDetectorParam (OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam &i_param_) |
| 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) |
| bool | getObjectGeneralizedConstraintWrenches (OpenHRP::ObjectContactTurnaroundDetectorService::objectGeneralizedConstraintWrenchesParam &o_param) |
| ObjectContactTurnaroundDetector (RTC::Manager *manager) | |
| virtual RTC::ReturnCode_t | onActivated (RTC::UniqueId ec_id) |
| virtual RTC::ReturnCode_t | onDeactivated (RTC::UniqueId ec_id) |
| virtual RTC::ReturnCode_t | onExecute (RTC::UniqueId ec_id) |
| virtual RTC::ReturnCode_t | onFinalize () |
| virtual RTC::ReturnCode_t | onInitialize () |
| bool | setObjectContactTurnaroundDetectorParam (const OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam &i_param_) |
| void | startObjectContactTurnaroundDetection (const double i_ref_diff_wrench, const double i_max_time, const OpenHRP::ObjectContactTurnaroundDetectorService::StrSequence &i_ee_names) |
| bool | startObjectContactTurnaroundDetectionForGeneralizedWrench () |
| virtual | ~ObjectContactTurnaroundDetector () |
Protected Attributes | |
| TimedBooleanSeq | m_contactStates |
| InPort< TimedBooleanSeq > | m_contactStatesIn |
| std::vector< TimedDoubleSeq > | m_force |
| std::vector< InPort < TimedDoubleSeq > * > | m_forceIn |
| RTC::CorbaPort | m_ObjectContactTurnaroundDetectorServicePort |
| TimedDoubleSeq | m_octdData |
| OutPort< TimedDoubleSeq > | m_octdDataOut |
| TimedDoubleSeq | m_qCurrent |
| InPort< TimedDoubleSeq > | m_qCurrentIn |
| TimedOrientation3D | m_rpy |
| InPort< TimedOrientation3D > | m_rpyIn |
| ObjectContactTurnaroundDetectorService_impl | m_service0 |
Private Member Functions | |
| void | calcFootMidCoords (hrp::Vector3 &new_foot_mid_pos, hrp::Matrix33 &new_foot_mid_rot) |
| void | calcFootOriginCoords (hrp::Vector3 &foot_origin_pos, hrp::Matrix33 &foot_origin_rot) |
| void | calcObjectContactTurnaroundDetectorState () |
| OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode | checkObjectContactTurnaroundDetectionCommon (const size_t index) |
| std::string | getEENameFromSensorName (const std::string &sensor_name) |
| void | updateRootLinkPosRot (TimedOrientation3D tmprpy) |
Private Attributes | |
| int | dummy |
| std::map< std::string, ee_trans > | ee_map |
| int | loop |
| unsigned int | m_debugLevel |
| double | m_dt |
| coil::Mutex | m_mutex |
| hrp::BodyPtr | m_robot |
| boost::shared_ptr < ObjectContactTurnaroundDetectorBase > | octd |
| hrp::Vector3 | octd_axis |
| std::vector< std::string > | octd_sensor_names |
Definition at line 38 of file ObjectContactTurnaroundDetector.h.
Definition at line 41 of file ObjectContactTurnaroundDetector.cpp.
Definition at line 57 of file ObjectContactTurnaroundDetector.cpp.
| void ObjectContactTurnaroundDetector::calcFootMidCoords | ( | hrp::Vector3 & | new_foot_mid_pos, |
| hrp::Matrix33 & | new_foot_mid_rot | ||
| ) | [private] |
Definition at line 322 of file ObjectContactTurnaroundDetector.cpp.
| void ObjectContactTurnaroundDetector::calcFootOriginCoords | ( | hrp::Vector3 & | foot_origin_pos, |
| hrp::Matrix33 & | foot_origin_rot | ||
| ) | [private] |
Definition at line 336 of file ObjectContactTurnaroundDetector.cpp.
Definition at line 369 of file ObjectContactTurnaroundDetector.cpp.
| OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode ObjectContactTurnaroundDetector::checkObjectContactTurnaroundDetection | ( | ) |
Definition at line 478 of file ObjectContactTurnaroundDetector.cpp.
| OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode ObjectContactTurnaroundDetector::checkObjectContactTurnaroundDetectionCommon | ( | const size_t | index | ) | [private] |
Definition at line 452 of file ObjectContactTurnaroundDetector.cpp.
| bool ObjectContactTurnaroundDetector::checkObjectContactTurnaroundDetectionForGeneralizedWrench | ( | OpenHRP::ObjectContactTurnaroundDetectorService::DetectorModeSequence_out | o_dms | ) |
Definition at line 484 of file ObjectContactTurnaroundDetector.cpp.
| std::string ObjectContactTurnaroundDetector::getEENameFromSensorName | ( | const std::string & | sensor_name | ) | [inline, private] |
Definition at line 159 of file ObjectContactTurnaroundDetector.h.
| bool ObjectContactTurnaroundDetector::getObjectContactTurnaroundDetectorParam | ( | OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam & | i_param_ | ) |
Definition at line 568 of file ObjectContactTurnaroundDetector.cpp.
| bool ObjectContactTurnaroundDetector::getObjectForcesMoments | ( | OpenHRP::ObjectContactTurnaroundDetectorService::Dbl3Sequence_out | o_forces, |
| OpenHRP::ObjectContactTurnaroundDetectorService::Dbl3Sequence_out | o_moments, | ||
| OpenHRP::ObjectContactTurnaroundDetectorService::DblSequence3_out | o_3dofwrench, | ||
| double & | o_fric_coeff_wrench | ||
| ) |
Definition at line 628 of file ObjectContactTurnaroundDetector.cpp.
| bool ObjectContactTurnaroundDetector::getObjectGeneralizedConstraintWrenches | ( | OpenHRP::ObjectContactTurnaroundDetectorService::objectGeneralizedConstraintWrenchesParam & | o_param | ) |
Definition at line 653 of file ObjectContactTurnaroundDetector.cpp.
| RTC::ReturnCode_t ObjectContactTurnaroundDetector::onActivated | ( | RTC::UniqueId | ec_id | ) | [virtual] |
Reimplemented from RTC::RTObject_impl.
Definition at line 239 of file ObjectContactTurnaroundDetector.cpp.
| RTC::ReturnCode_t ObjectContactTurnaroundDetector::onDeactivated | ( | RTC::UniqueId | ec_id | ) | [virtual] |
Reimplemented from RTC::RTObject_impl.
Definition at line 245 of file ObjectContactTurnaroundDetector.cpp.
| RTC::ReturnCode_t ObjectContactTurnaroundDetector::onExecute | ( | RTC::UniqueId | ec_id | ) | [virtual] |
Reimplemented from RTC::RTObject_impl.
Definition at line 252 of file ObjectContactTurnaroundDetector.cpp.
| RTC::ReturnCode_t ObjectContactTurnaroundDetector::onFinalize | ( | void | ) | [virtual] |
Reimplemented from RTC::RTObject_impl.
Definition at line 220 of file ObjectContactTurnaroundDetector.cpp.
Reimplemented from RTC::RTObject_impl.
Definition at line 62 of file ObjectContactTurnaroundDetector.cpp.
| bool ObjectContactTurnaroundDetector::setObjectContactTurnaroundDetectorParam | ( | const OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam & | i_param_ | ) |
Definition at line 494 of file ObjectContactTurnaroundDetector.cpp.
| void ObjectContactTurnaroundDetector::startObjectContactTurnaroundDetection | ( | const double | i_ref_diff_wrench, |
| const double | i_max_time, | ||
| const OpenHRP::ObjectContactTurnaroundDetectorService::StrSequence & | i_ee_names | ||
| ) |
Definition at line 435 of file ObjectContactTurnaroundDetector.cpp.
Definition at line 445 of file ObjectContactTurnaroundDetector.cpp.
| void ObjectContactTurnaroundDetector::updateRootLinkPosRot | ( | TimedOrientation3D | tmprpy | ) | [private] |
Definition at line 420 of file ObjectContactTurnaroundDetector.cpp.
int ObjectContactTurnaroundDetector::dummy [private] |
Definition at line 174 of file ObjectContactTurnaroundDetector.h.
std::map<std::string, ee_trans> ObjectContactTurnaroundDetector::ee_map [private] |
Definition at line 164 of file ObjectContactTurnaroundDetector.h.
int ObjectContactTurnaroundDetector::loop [private] |
Definition at line 175 of file ObjectContactTurnaroundDetector.h.
TimedBooleanSeq ObjectContactTurnaroundDetector::m_contactStates [protected] |
Definition at line 116 of file ObjectContactTurnaroundDetector.h.
InPort<TimedBooleanSeq> ObjectContactTurnaroundDetector::m_contactStatesIn [protected] |
Definition at line 117 of file ObjectContactTurnaroundDetector.h.
unsigned int ObjectContactTurnaroundDetector::m_debugLevel [private] |
Definition at line 173 of file ObjectContactTurnaroundDetector.h.
double ObjectContactTurnaroundDetector::m_dt [private] |
Definition at line 170 of file ObjectContactTurnaroundDetector.h.
std::vector<TimedDoubleSeq> ObjectContactTurnaroundDetector::m_force [protected] |
Definition at line 112 of file ObjectContactTurnaroundDetector.h.
std::vector<InPort<TimedDoubleSeq> *> ObjectContactTurnaroundDetector::m_forceIn [protected] |
Definition at line 113 of file ObjectContactTurnaroundDetector.h.
Definition at line 172 of file ObjectContactTurnaroundDetector.h.
RTC::CorbaPort ObjectContactTurnaroundDetector::m_ObjectContactTurnaroundDetectorServicePort [protected] |
Definition at line 130 of file ObjectContactTurnaroundDetector.h.
TimedDoubleSeq ObjectContactTurnaroundDetector::m_octdData [protected] |
Definition at line 123 of file ObjectContactTurnaroundDetector.h.
OutPort<TimedDoubleSeq> ObjectContactTurnaroundDetector::m_octdDataOut [protected] |
Definition at line 124 of file ObjectContactTurnaroundDetector.h.
TimedDoubleSeq ObjectContactTurnaroundDetector::m_qCurrent [protected] |
Definition at line 110 of file ObjectContactTurnaroundDetector.h.
InPort<TimedDoubleSeq> ObjectContactTurnaroundDetector::m_qCurrentIn [protected] |
Definition at line 111 of file ObjectContactTurnaroundDetector.h.
Definition at line 171 of file ObjectContactTurnaroundDetector.h.
TimedOrientation3D ObjectContactTurnaroundDetector::m_rpy [protected] |
Definition at line 114 of file ObjectContactTurnaroundDetector.h.
InPort<TimedOrientation3D> ObjectContactTurnaroundDetector::m_rpyIn [protected] |
Definition at line 115 of file ObjectContactTurnaroundDetector.h.
Definition at line 136 of file ObjectContactTurnaroundDetector.h.
boost::shared_ptr<ObjectContactTurnaroundDetectorBase > ObjectContactTurnaroundDetector::octd [private] |
Definition at line 167 of file ObjectContactTurnaroundDetector.h.
Definition at line 169 of file ObjectContactTurnaroundDetector.h.
std::vector<std::string> ObjectContactTurnaroundDetector::octd_sensor_names [private] |
Definition at line 168 of file ObjectContactTurnaroundDetector.h.