CollisionAvoidanceCore.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package ...
17  * @author Jianfeng Gao ( jianfeng dot gao at kit dot edu )
18  * @date 2024
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #pragma once
24 
25 #include <VirtualRobot/VirtualRobot.h>
26 
28 
30 #include <armarx/control/common/control_law/aron/CollisionAvoidanceConfig.aron.generated.h>
31 
32 #include <simox/control/dynamics/RBDLModel.h>
33 #include <simox/control/environment/CollisionRobotInterface.h>
34 #include <simox/control/environment/fwd.h>
35 #include <simox/control/impl/simox/robot/Robot.h>
36 #include <simox/control/robot/RobotInterface.h>
37 
39 {
40 
42 
43  /**
44  * @defgroup Library-CollisionAvoidanceBase CollisionAvoidanceBase
45  * @ingroup Library-RobotUnit-NJointControllers
46  * A description of the library CollisionAvoidanceBase.
47  *
48  * @class CollisionAvoidanceBase
49  * @ingroup Library-CollisionAvoidanceBase
50  * @brief Brief description of class CollisionAvoidanceBase.
51  *
52  * Detailed description of class CollisionAvoidanceBase.
53  */
55  {
56 
57  public:
61  using CtrlConfig = law::arondto::CollisionAvoidanceConfig;
62  using Config = law::arondto::CollisionAvoidanceConfigDict;
63  using RtStatus = law::CollisionAvoidanceController::RtStatusForSafetyStrategy;
64 
65  using CollisionRobot = simox::control::environment::CollisionRobotInterface;
66  using DynamicsModel = simox::control::dynamics::RBDLModel;
67 
68  struct NodeSetData
69  {
70  std::string nodeSetName;
71 
72  /// !!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
73  VirtualRobot::RobotNodeSetPtr rtRNS;
74 
75  /// controller (maths)
77  RtStatus rts; // should only be used in rt thread
79 
80  /// self-collision avoidance
81  std::unique_ptr<DynamicsModel> dynamicsModel;
84 
85  NodeSetData(const VirtualRobot::RobotPtr& rtRobot,
86  const std::string& robotNodeSetName,
87  const SCRobot& scRobot,
89  const Config& c);
90 
91  void reset(const Config& c);
92  };
93 
94  CollisionAvoidanceBase(const VirtualRobot::RobotPtr& rtRobot, const Config& cfg);
96 
97  void rtCollisionChecking();
98  void rtLimbControllerRun(const std::string& robotNodeSetName,
99  const Eigen::VectorXf& qpos,
100  const Eigen::VectorXf& qvelFiltered,
101  float torqueLimit,
102  const Eigen::VectorXf& impedanceJointTorque);
103  void rtPreActivate();
104  void rtPostDeactivate();
105  void updateRtConfigFromUser();
106 
107  std::map<std::string, NodeSetData> collLimb;
108  Config userCfg; // used in nonRT
110 
111  void validateConfigData(const Config& cfg);
112  void setUserCfg(const Config& cfg);
113 
114  protected:
115  std::unique_ptr<CollisionRobot> collisionRobot;
116  std::unique_ptr<SCRobot> scRobot;
118 
119  std::vector<std::string> actuatedJointNames; /// TODO, rename to actuatedJointNames
120  Eigen::VectorXd qposActuatedJoints;
121  std::vector<unsigned int> translationJointIndex;
122  //int qposActuatedJointsIndex;
123 
124  private:
125  float preFilterDistance = 0.6; // in meter
126  // int maxCollisionPairs = 100;
127 
128  const bool reduceModel = false; // not needed anymore
129 
130  simox::control::environment::CompDistArgs selfColAvoidanceArgs;
131 
132  Config rtCfg; // used in RT
133  VirtualRobot::RobotPtr rtRobot;
134  };
135 
136  using CollisionAvoidanceBasePtr = std::shared_ptr<CollisionAvoidanceBase>;
137 } // namespace armarx::control::njoint_controller::core
armarx::control::njoint_controller::core::CollisionAvoidanceBase::translationJointIndex
std::vector< unsigned int > translationJointIndex
Definition: CollisionAvoidanceCore.h:121
armarx::control::njoint_controller::core::CollisionAvoidanceBase::setUserCfg
void setUserCfg(const Config &cfg)
Definition: CollisionAvoidanceCore.cpp:260
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::collisionRobotIndices
CollisionRobotIndices collisionRobotIndices
Definition: CollisionAvoidanceCore.h:83
armarx::control::njoint_controller::core::CollisionAvoidanceBase::~CollisionAvoidanceBase
~CollisionAvoidanceBase()
Definition: CollisionAvoidanceCore.cpp:128
armarx::control::njoint_controller::core::CollisionAvoidanceBase::CollisionAvoidanceBase
CollisionAvoidanceBase(const VirtualRobot::RobotPtr &rtRobot, const Config &cfg)
Definition: CollisionAvoidanceCore.cpp:17
armarx::control::common::control_law::CollisionAvoidanceController::CollisionRobotIndices
std::unordered_map< unsigned int, const simox::control::robot::NodeInterface * > CollisionRobotIndices
Definition: CollisionAvoidance.h:61
armarx::control::njoint_controller::core::CollisionAvoidanceBase::collisionPairs
DistanceResults collisionPairs
Definition: CollisionAvoidanceCore.h:117
armarx::control::njoint_controller::core::CollisionAvoidanceBase::rtPreActivate
void rtPreActivate()
Definition: CollisionAvoidanceCore.cpp:162
armarx::control::njoint_controller::core::CollisionAvoidanceBase::userCfg
Config userCfg
Definition: CollisionAvoidanceCore.h:108
armarx::control::common::control_law::CollisionAvoidanceController::DistanceResults
std::vector< DistanceResult > DistanceResults
Definition: CollisionAvoidance.h:57
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::NodeSetData
NodeSetData(const VirtualRobot::RobotPtr &rtRobot, const std::string &robotNodeSetName, const SCRobot &scRobot, const DistanceResults &collisionPairs, const Config &c)
Definition: CollisionAvoidanceCore.cpp:133
armarx::control::njoint_controller::core::CollisionAvoidanceBase::actuatedJointNames
std::vector< std::string > actuatedJointNames
Definition: CollisionAvoidanceCore.h:119
armarx::control::njoint_controller::core::CollisionAvoidanceBase::scRobot
std::unique_ptr< SCRobot > scRobot
Definition: CollisionAvoidanceCore.h:116
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
armarx::control::njoint_controller::core
This file is part of ArmarX.
Definition: CollisionAvoidanceCore.cpp:14
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::bufferRTtoPublish
armarx::TripleBuffer< RtStatus > bufferRTtoPublish
Definition: CollisionAvoidanceCore.h:78
armarx::control::njoint_controller::core::CollisionAvoidanceBasePtr
std::shared_ptr< CollisionAvoidanceBase > CollisionAvoidanceBasePtr
Definition: CollisionAvoidanceCore.h:136
armarx::control::njoint_controller::core::CollisionAvoidanceBase::collisionRobot
std::unique_ptr< CollisionRobot > collisionRobot
Definition: CollisionAvoidanceCore.h:115
armarx::control::njoint_controller::core::CollisionAvoidanceBase::bufferCfgUserToRT
armarx::TripleBuffer< Config > bufferCfgUserToRT
Definition: CollisionAvoidanceCore.h:109
armarx::control::njoint_controller::core::CollisionAvoidanceBase::DistanceResults
law::CollisionAvoidanceController::DistanceResults DistanceResults
Definition: CollisionAvoidanceCore.h:59
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::controller
law::CollisionAvoidanceController controller
controller (maths)
Definition: CollisionAvoidanceCore.h:76
armarx::control::common::control_law::CollisionAvoidanceController::SCRobot
::simox::control::robot::RobotInterface SCRobot
Definition: CollisionAvoidance.h:55
armarx::control::njoint_controller::core::CollisionAvoidanceBase::SCRobot
law::CollisionAvoidanceController::SCRobot SCRobot
Definition: CollisionAvoidanceCore.h:58
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData
Definition: CollisionAvoidanceCore.h:68
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::rts
RtStatus rts
Definition: CollisionAvoidanceCore.h:77
armarx::control::njoint_controller::core::CollisionAvoidanceBase::qposActuatedJoints
Eigen::VectorXd qposActuatedJoints
TODO, rename to actuatedJointNames.
Definition: CollisionAvoidanceCore.h:120
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::dynamicsModel
std::unique_ptr< DynamicsModel > dynamicsModel
self-collision avoidance
Definition: CollisionAvoidanceCore.h:81
armarx::control::njoint_controller::core::CollisionAvoidanceBase::updateRtConfigFromUser
void updateRtConfigFromUser()
Definition: CollisionAvoidanceCore.cpp:180
armarx::control::common::control_law::CollisionAvoidanceController
Definition: CollisionAvoidance.h:52
armarx::control::njoint_controller::core::CollisionAvoidanceBase::rtPostDeactivate
void rtPostDeactivate()
Definition: CollisionAvoidanceCore.cpp:171
armarx::control::njoint_controller::core::CollisionAvoidanceBase::CtrlConfig
law::arondto::CollisionAvoidanceConfig CtrlConfig
Definition: CollisionAvoidanceCore.h:61
armarx::control::njoint_controller::core::CollisionAvoidanceBase::CollisionRobot
simox::control::environment::CollisionRobotInterface CollisionRobot
Definition: CollisionAvoidanceCore.h:65
armarx::control::njoint_controller::core::CollisionAvoidanceBase::validateConfigData
void validateConfigData(const Config &cfg)
Definition: CollisionAvoidanceCore.cpp:248
armarx::control::common::control_law
This file is part of ArmarX.
Definition: aron_conversions.cpp:68
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::reset
void reset(const Config &c)
Definition: CollisionAvoidanceCore.cpp:155
armarx::control::njoint_controller::core::CollisionAvoidanceBase::RtStatus
law::CollisionAvoidanceController::RtStatusForSafetyStrategy RtStatus
Definition: CollisionAvoidanceCore.h:63
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::nodeSetName
std::string nodeSetName
Definition: CollisionAvoidanceCore.h:70
armarx::control::njoint_controller::core::CollisionAvoidanceBase::DynamicsModel
simox::control::dynamics::RBDLModel DynamicsModel
Definition: CollisionAvoidanceCore.h:66
armarx::control::njoint_controller::core::CollisionAvoidanceBase::CollisionRobotIndices
law::CollisionAvoidanceController::CollisionRobotIndices CollisionRobotIndices
Definition: CollisionAvoidanceCore.h:60
TripleBuffer.h
armarx::control::njoint_controller::core::CollisionAvoidanceBase::collLimb
std::map< std::string, NodeSetData > collLimb
Definition: CollisionAvoidanceCore.h:107
CollisionAvoidance.h
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::collisionPairs
const DistanceResults & collisionPairs
Definition: CollisionAvoidanceCore.h:82
armarx::control::njoint_controller::core::CollisionAvoidanceBase::NodeSetData::rtRNS
VirtualRobot::RobotNodeSetPtr rtRNS
!!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
Definition: CollisionAvoidanceCore.h:73
armarx::control::njoint_controller::core::CollisionAvoidanceBase::rtCollisionChecking
void rtCollisionChecking()
Definition: CollisionAvoidanceCore.cpp:188
armarx::control::njoint_controller::core::CollisionAvoidanceBase::Config
law::arondto::CollisionAvoidanceConfigDict Config
Definition: CollisionAvoidanceCore.h:62
armarx::control::njoint_controller::core::CollisionAvoidanceBase::rtLimbControllerRun
void rtLimbControllerRun(const std::string &robotNodeSetName, const Eigen::VectorXf &qpos, const Eigen::VectorXf &qvelFiltered, float torqueLimit, const Eigen::VectorXf &impedanceJointTorque)
Definition: CollisionAvoidanceCore.cpp:225
armarx::control::njoint_controller::core::CollisionAvoidanceBase
Brief description of class CollisionAvoidanceBase.
Definition: CollisionAvoidanceCore.h:54
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:19
armarx::TripleBuffer< RtStatus >