ObjectCollisionAvoidanceCore.h
Go to the documentation of this file.
1// namespace armarx::control::njoint_controller::core
2/*
3 * This file is part of ArmarX.
4 *
5 * ArmarX is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License version 2 as
7 * published by the Free Software Foundation.
8 *
9 * ArmarX is distributed in the hope that it will be useful, but
10 * WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
13 *
14 * You should have received a copy of the GNU General Public License
15 * along with this program. If not, see <http://www.gnu.org/licenses/>.
16 *
17 * @package ...
18 * @author Jianfeng Gao ( jianfeng dot gao at kit dot edu )
19 * @date 2024
20 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21 * GNU General Public License
22 */
23
24#pragma once
25
26#include <VirtualRobot/Robot.h>
27
28#include <simox/control/dynamics/RBDLModel.h>
29#include <simox/control/environment/CollisionRobotInterface.h>
30#include <simox/control/environment/fwd.h>
31#include <simox/control/impl/simox/robot/Robot.h>
32#include <simox/control/robot/RobotInterface.h>
33
35
37#include <armarx/control/common/control_law/aron/ObjectCollisionAvoidanceConfig.aron.generated.h>
39
41{
42
43 namespace law = armarx::control::common::control_law;
44
45 /**
46 * @defgroup Library-CollisionAvoidanceBase CollisionAvoidanceBase
47 * @ingroup Library-RobotUnit-NJointControllers
48 * A description of the library CollisionAvoidanceBase.
49 *
50 * @class ObjectCollisionAvoidanceBase
51 * @ingroup Library-CollisionAvoidanceBase
52 * @brief Brief description of class CollisionAvoidanceBase.
53 *
54 * Detailed description of class CollisionAvoidanceBase.
55 */
57 {
58
59 public:
60 using SCRobot = law::CollisionAvoidanceController::SCRobot;
61 using DistanceResults = law::CollisionAvoidanceController::DistanceResults;
62 using CollisionRobotIndices = law::CollisionAvoidanceController::CollisionRobotIndices;
63 using CtrlConfig = law::arondto::ObjectCollisionAvoidanceConfig;
64 using Config = law::arondto::ObjectCollisionAvoidanceConfigDict;
65 using RtStatus = law::CollisionAvoidanceController::RtStatusForSafetyStrategy;
66 using RecoveryState = law::CollisionAvoidanceController::RecoveryState;
67 using CollisionRobot = simox::control::environment::CollisionRobotInterface;
68 using DynamicsModel = simox::control::dynamics::RBDLModel;
69
71 {
72 std::string nodeSetName;
73
74 /// !!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
75 VirtualRobot::RobotNodeSetPtr rtRNS;
76
77 /// controller (maths)
78 law::ObjectCollisionAvoidanceController controller;
79 RtStatus rts; // should only be used in rt thread
80
81 /// recovery strategy
84
87
88 /// self-collision avoidance
89 std::unique_ptr<DynamicsModel> dynamicsModel;
92
94 const std::string& robotNodeSetName,
95 const SCRobot& scRobot,
97 const Config& c,
98 const std::vector<size_t>& velCtrlIndex);
99
100 void reset(const Config& c, const std::vector<size_t>& velCtrlIndex);
101 };
102
104 const VirtualRobot::RobotPtr& rtRobot,
105 const Config& cfg,
106 const std::map<std::string, std::vector<size_t>>& velCtrlIndices);
108
109 virtual void rtCollisionChecking();
110 void rtLimbControllerRun(const std::string& robotNodeSetName,
111 float torqueLimit,
112 float jointVelLimit,
114 void rtPreActivate();
115 void rtPostDeactivate();
117
118 std::vector<hpp::fcl::CollisionObject> userCollisionObjects;
120 void updateUserCollisionObjects(const std::vector<hpp::fcl::CollisionObject>&);
123
124 std::map<std::string, NodeSetData> collLimb;
125 Config userCfg; // used in nonRT
127
128 void validateConfigData(const Config& cfg);
129 void setUserCfg(const Config& cfg);
130
131 // TODO make protected again, publish collision geometry
132 std::unique_ptr<CollisionRobot> collisionRobot;
134
135
136 protected:
138 std::unique_ptr<SCRobot> scRobot;
139 VirtualRobot::RobotNodeSetPtr scRobotNodeSet;
140
144
145 std::vector<std::string> actuatedJointNames;
146 Eigen::VectorXd qposActuatedJoints;
147
148 std::vector<unsigned int> translationJointIndex;
149 //int qposActuatedJointsIndex;
150
151 /// !!! individualColObjects has to be set to true !!!
152 /// if not set to true, the body and the arms become attractive, be aware
153 const simox::control::environment::CompDistArgs compDistArgs =
154 simox::control::environment::CompDistArgs{.nearestPoints = true,
155 .individualColObjects = true};
156
157 Config rtCfg; // used in RT
158
159 private:
160 float preFilterDistance = 0.6; // in meter
161 std::map<std::string, std::vector<size_t>> velCtrlIdx;
162 // int maxCollisionPairs = 100;
163
164 const bool reduceModel = false; // TODO check here! not needed anymore for a7, but for a6
165
166 simox::control::environment::CompDistArgs selfColAvoidanceArgs;
167
169 std::vector<hpp::fcl::CollisionObject> rtCollisionObjects;
170 VirtualRobot::RobotNodeSetPtr rtRobotNodeSet;
171 };
172
173 using ObjectCollisionAvoidanceBasePtr = std::shared_ptr<ObjectCollisionAvoidanceBase>;
174} // namespace armarx::control::njoint_controller::core
constexpr T c
A simple triple buffer for lockfree comunication between a single writer and a single reader.
law::CollisionAvoidanceController::CollisionRobotIndices CollisionRobotIndices
law::CollisionAvoidanceController::RtStatusForSafetyStrategy RtStatus
ObjectCollisionAvoidanceBase(const VirtualRobot::RobotPtr &rtRobot, const Config &cfg, const std::map< std::string, std::vector< size_t > > &velCtrlIndices)
void updateUserCollisionObjects(const std::vector< hpp::fcl::CollisionObject > &)
armarx::TripleBuffer< std::tuple< DistanceResults, std::vector< hpp::fcl::CollisionObject > > > bufferCollisionObjectsUserToRt
void rtLimbControllerRun(const std::string &robotNodeSetName, float torqueLimit, float jointVelLimit, common::control_law::TSCtrlRtStatus &rts)
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
std::shared_ptr< ObjectCollisionAvoidanceBase > ObjectCollisionAvoidanceBasePtr
VirtualRobot::RobotNodeSetPtr rtRNS
!!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
NodeSetData(const VirtualRobot::RobotPtr &rtRobot, const std::string &robotNodeSetName, const SCRobot &scRobot, const DistanceResults &collisionPairs, const Config &c, const std::vector< size_t > &velCtrlIndex)