26#include <VirtualRobot/Robot.h>
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>
37#include <armarx/control/common/control_law/aron/ObjectCollisionAvoidanceConfig.aron.generated.h>
43 namespace law = armarx::control::common::control_law;
60 using SCRobot = law::CollisionAvoidanceController::SCRobot;
63 using CtrlConfig = law::arondto::ObjectCollisionAvoidanceConfig;
64 using Config = law::arondto::ObjectCollisionAvoidanceConfigDict;
65 using RtStatus = law::CollisionAvoidanceController::RtStatusForSafetyStrategy;
75 VirtualRobot::RobotNodeSetPtr
rtRNS;
94 const std::string& robotNodeSetName,
98 const std::vector<size_t>& velCtrlIndex);
100 void reset(
const Config&
c,
const std::vector<size_t>& velCtrlIndex);
106 const std::map<std::string, std::vector<size_t>>& velCtrlIndices);
154 simox::control::environment::CompDistArgs{.nearestPoints =
true,
155 .individualColObjects =
true};
160 float preFilterDistance = 0.6;
161 std::map<std::string, std::vector<size_t>> velCtrlIdx;
164 const bool reduceModel =
false;
166 simox::control::environment::CompDistArgs selfColAvoidanceArgs;
169 std::vector<hpp::fcl::CollisionObject> rtCollisionObjects;
170 VirtualRobot::RobotNodeSetPtr rtRobotNodeSet;
A simple triple buffer for lockfree comunication between a single writer and a single reader.
std::vector< std::string > actuatedJointNames
const simox::control::environment::CompDistArgs compDistArgs
!
virtual ~ObjectCollisionAvoidanceBase()
Eigen::Matrix< double, 4, 4 > globalPose
DistanceResults userExternalCollisionPairs
simox::control::dynamics::RBDLModel DynamicsModel
law::CollisionAvoidanceController::DistanceResults DistanceResults
std::vector< unsigned int > translationJointIndex
std::unique_ptr< CollisionRobot > collisionRobot
armarx::TripleBuffer< Config > bufferCfgUserToRT
DistanceResults collisionPairs
void deleteUserCollisionObjects()
law::CollisionAvoidanceController::CollisionRobotIndices CollisionRobotIndices
Eigen::VectorXd qposActuatedJoints
law::CollisionAvoidanceController::RtStatusForSafetyStrategy RtStatus
virtual void rtCollisionChecking()
simox::control::environment::CollisionRobotInterface CollisionRobot
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)
law::arondto::ObjectCollisionAvoidanceConfig CtrlConfig
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
law::CollisionAvoidanceController::RecoveryState RecoveryState
std::shared_ptr< class Robot > RobotPtr
This file is part of ArmarX.
This file is part of ArmarX.
std::shared_ptr< ObjectCollisionAvoidanceBase > ObjectCollisionAvoidanceBasePtr
armarx::TripleBuffer< RecoveryState > bufferRecoveryStateSelfColl
CollisionRobotIndices collisionRobotIndices
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