3#include <VirtualRobot/Nodes/RobotNode.h>
4#include <VirtualRobot/RobotNodeSet.h>
6#include <simox/control/environment/CollisionRobot.h>
7#include <simox/control/impl/simox/robot/Robot.h>
23 const std::map<std::string, std::vector<size_t>>& velCtrlIndices) :
32 velCtrlIdx = velCtrlIndices;
35 std::vector<std::string> tcpNodeNames;
36 for (
const auto& pair :
rtCfg.ctrlCfg)
38 const auto nodeset = rtRobot->getRobotNodeSet(pair.first);
39 const std::string tcpName = nodeset->getTCP()->getName();
40 tcpNodeNames.push_back(tcpName);
41 if (pair.second.selfDistanceThreshold > preFilterDistance)
43 preFilterDistance = pair.second.selfDistanceThreshold;
45 if (pair.second.objectDistanceThreshold > preFilterDistance)
47 preFilterDistance = pair.second.objectDistanceThreshold;
54 ARMARX_CHECK(rtRobot->hasRobotNodeSet(cfg.actuatedRobotNodeSetName));
55 rtRobotNodeSet = rtRobot->getRobotNodeSet(cfg.actuatedRobotNodeSetName);
59 scRobot = std::make_unique<simox::control::simox::robot::Robot>(
61 scRobot->setGlobalPose(Eigen::Isometry3d::Identity());
66 ARMARX_DEBUG <<
"Creating robot model for collision computation using default primitive "
67 "models and models with id "
68 <<
rtCfg.primitiveModelParts;
71 std::make_unique<simox::control::environment::CollisionRobot<hpp::fcl::OBBRSS>>(
73 simox::control::environment::CollisionRobotParams{.loadDefaultPrimitiveModel =
true,
75 rtCfg.primitiveModelParts,
87 const auto node = rtRobot->getRobotNode(nodeName);
88 if (node->isTranslationalJoint())
97 for (
const auto& pair :
rtCfg.ctrlCfg)
105 velCtrlIdx.at(pair.first));
109 ARMARX_DEBUG <<
"Creating index to node mapping for collision robot:";
110 std::unordered_set<unsigned int> consideredIndices;
114 for (
const auto& [
index, node] :
data.collisionRobotIndices)
117 <<
" for limb " << name;
118 consideredIndices.insert(
index);
122 ARMARX_DEBUG <<
"Initial computation of all self collision pairs";
124 selfColAvoidanceArgs =
125 simox::control::environment::CompDistArgs{.updatePose =
false,
126 .nearestPoints =
true,
127 .individualColObjects =
true,
128 .allowIndices = consideredIndices};
134 collisionRobot->computeMinimumSelfCollisionDistance(selfColAvoidanceArgs);
135 const int nElements = distanceResults.size();
137 for (
const auto& distanceResult : distanceResults)
140 <<
collisionRobot->getNodes().at(distanceResult.node1).getName() <<
" and "
142 <<
". Initial distance: " << distanceResult.minDistance <<
"m";
145 ARMARX_DEBUG <<
"Reserving space for " << nElements <<
" collision pairs";
157 const std::string& robotNodeSetName,
161 const std::vector<size_t>& velCtrlIndex) :
163 rtRNS(rtRobot->getRobotNodeSet(robotNodeSetName)),
180 const std::vector<size_t>& velCtrlIndex)
182 rts.reset(
c.ctrlCfg.at(
rtRNS->getName()),
187 rts.objectCollisionNullSpaceWeights =
189 c.ctrlCfg.at(
rtRNS->getName()).objectCollActivatorZ1,
190 c.ctrlCfg.at(
rtRNS->getName()).objectCollActivatorZ2);
200 pair.second.rts.rtPreActivate(
userCfg.ctrlCfg.at(pair.first));
201 pair.second.recoveryStateObjColl.reset();
202 pair.second.recoveryStateSelfColl.reset();
211 pair.second.reset(
rtCfg, velCtrlIdx.at(pair.first));
248 scRobotNodeSet->setJointValues(rtRobotNodeSet->getJointValuesEigen());
250 globalPose = rtRobot->getGlobalPose().matrix().cast<
double>();
255 const auto time = IceUtil::Time::now();
259 const double collisionPairTime = (IceUtil::Time::now() - time).toMicroSecondsDouble();
263 pair.second.rts.collisionPairTime = collisionPairTime;
276 law::TSCtrlRtStatus& rts)
278 auto& arm =
collLimb.at(robotNodeSetName);
281 arm.controller.run(
rtCfg.ctrlCfg.at(robotNodeSetName),
283 arm.recoveryStateSelfColl,
284 arm.recoveryStateObjColl,
287 arm.collisionRobotIndices,
292 arm.bufferRTtoPublish.getWriteBuffer() = arm.rts;
293 arm.bufferRTtoPublish.commitWrite();
295 arm.bufferRecoveryStateSelfColl.getWriteBuffer() = arm.recoveryStateSelfColl;
296 arm.bufferRecoveryStateSelfColl.commitWrite();
305 for (
auto& pair : cfg.ctrlCfg)
333 std::get<0>(writeBuffer).reserve(0);
340 const std::vector<hpp::fcl::CollisionObject>& collisionObjects)
342 const unsigned int nElements =
344 ARMARX_INFO <<
"There are " << collisionObjects.size() <<
" collision objects";
345 ARMARX_INFO <<
"Reserving space for " << nElements <<
" collision pairs";
349 std::get<0>(writeBuffer).reserve(nElements);
350 std::get<1>(writeBuffer) = collisionObjects;
#define ARMARX_CHECK_NOT_EMPTY(c)
std::vector< std::string > actuatedJointNames
const simox::control::environment::CompDistArgs compDistArgs
!
virtual ~ObjectCollisionAvoidanceBase()
Eigen::Matrix< double, 4, 4 > globalPose
law::CollisionAvoidanceController::DistanceResults DistanceResults
std::vector< unsigned int > translationJointIndex
std::unique_ptr< CollisionRobot > collisionRobot
armarx::TripleBuffer< Config > bufferCfgUserToRT
DistanceResults collisionPairs
void deleteUserCollisionObjects()
Eigen::VectorXd qposActuatedJoints
virtual void rtCollisionChecking()
std::vector< hpp::fcl::CollisionObject > userCollisionObjects
DistanceResults externalCollisionPairs
ObjectCollisionAvoidanceBase(const VirtualRobot::RobotPtr &rtRobot, const Config &cfg, const std::map< std::string, std::vector< size_t > > &velCtrlIndices)
std::unique_ptr< SCRobot > scRobot
void updateUserCollisionObjects(const std::vector< hpp::fcl::CollisionObject > &)
void setUserCfg(const Config &cfg)
law::arondto::ObjectCollisionAvoidanceConfigDict Config
law::CollisionAvoidanceController::SCRobot SCRobot
void validateConfigData(const Config &cfg)
armarx::TripleBuffer< std::tuple< DistanceResults, std::vector< hpp::fcl::CollisionObject > > > bufferCollisionObjectsUserToRt
void updateRtConfigFromUser()
VirtualRobot::RobotNodeSetPtr scRobotNodeSet
void updateRtCollisionObjects()
void rtLimbControllerRun(const std::string &robotNodeSetName, float torqueLimit, float jointVelLimit, common::control_law::TSCtrlRtStatus &rts)
std::map< std::string, NodeSetData > collLimb
#define ARMARX_CHECK_GREATER(lhs, rhs)
This macro evaluates whether lhs is greater (>) than rhs and if it turns out to be false it will thro...
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_CHECK_NONNEGATIVE(number)
Check whether number is nonnegative (>= 0).
#define ARMARX_INFO
The normal logging level.
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
std::shared_ptr< class Robot > RobotPtr
void validateConfigData(const arondto::CollisionAvoidanceConfig &cfg)
Eigen::Vector4f calculateTransitionWeights(float z1, float z2)
helper functions
This file is part of ArmarX.
armarx::TripleBuffer< RecoveryState > bufferRecoveryStateSelfColl
RecoveryState recoveryStateObjColl
VirtualRobot::RobotNodeSetPtr rtRNS
!!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
void reset(const Config &c, const std::vector< size_t > &velCtrlIndex)
std::unique_ptr< DynamicsModel > dynamicsModel
self-collision avoidance
RecoveryState recoveryStateSelfColl
recovery strategy
armarx::TripleBuffer< RtStatus > bufferRTtoPublish
NodeSetData(const VirtualRobot::RobotPtr &rtRobot, const std::string &robotNodeSetName, const SCRobot &scRobot, const DistanceResults &collisionPairs, const Config &c, const std::vector< size_t > &velCtrlIndex)
const DistanceResults & collisionPairs