Go to the documentation of this file.
25 #include <VirtualRobot/VirtualRobot.h>
30 #include <armarx/control/common/control_law/aron/CollisionAvoidanceConfig.aron.generated.h>
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>
61 using CtrlConfig = law::arondto::CollisionAvoidanceConfig;
62 using Config = law::arondto::CollisionAvoidanceConfigDict;
63 using RtStatus = law::CollisionAvoidanceController::RtStatusForSafetyStrategy;
73 VirtualRobot::RobotNodeSetPtr
rtRNS;
86 const std::string& robotNodeSetName,
99 const Eigen::VectorXf& qpos,
100 const Eigen::VectorXf& qvelFiltered,
102 const Eigen::VectorXf& impedanceJointTorque);
125 float preFilterDistance = 0.6;
128 const bool reduceModel =
false;
130 simox::control::environment::CompDistArgs selfColAvoidanceArgs;
std::vector< unsigned int > translationJointIndex
void setUserCfg(const Config &cfg)
CollisionRobotIndices collisionRobotIndices
~CollisionAvoidanceBase()
CollisionAvoidanceBase(const VirtualRobot::RobotPtr &rtRobot, const Config &cfg)
std::unordered_map< unsigned int, const simox::control::robot::NodeInterface * > CollisionRobotIndices
DistanceResults collisionPairs
std::vector< DistanceResult > DistanceResults
NodeSetData(const VirtualRobot::RobotPtr &rtRobot, const std::string &robotNodeSetName, const SCRobot &scRobot, const DistanceResults &collisionPairs, const Config &c)
std::vector< std::string > actuatedJointNames
std::unique_ptr< SCRobot > scRobot
This file is part of ArmarX.
armarx::TripleBuffer< RtStatus > bufferRTtoPublish
std::shared_ptr< CollisionAvoidanceBase > CollisionAvoidanceBasePtr
std::unique_ptr< CollisionRobot > collisionRobot
armarx::TripleBuffer< Config > bufferCfgUserToRT
law::CollisionAvoidanceController::DistanceResults DistanceResults
law::CollisionAvoidanceController controller
controller (maths)
::simox::control::robot::RobotInterface SCRobot
law::CollisionAvoidanceController::SCRobot SCRobot
Eigen::VectorXd qposActuatedJoints
TODO, rename to actuatedJointNames.
std::unique_ptr< DynamicsModel > dynamicsModel
self-collision avoidance
void updateRtConfigFromUser()
law::arondto::CollisionAvoidanceConfig CtrlConfig
simox::control::environment::CollisionRobotInterface CollisionRobot
void validateConfigData(const Config &cfg)
This file is part of ArmarX.
void reset(const Config &c)
law::CollisionAvoidanceController::RtStatusForSafetyStrategy RtStatus
simox::control::dynamics::RBDLModel DynamicsModel
law::CollisionAvoidanceController::CollisionRobotIndices CollisionRobotIndices
std::map< std::string, NodeSetData > collLimb
const DistanceResults & collisionPairs
VirtualRobot::RobotNodeSetPtr rtRNS
!!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
void rtCollisionChecking()
law::arondto::CollisionAvoidanceConfigDict Config
void rtLimbControllerRun(const std::string &robotNodeSetName, const Eigen::VectorXf &qpos, const Eigen::VectorXf &qvelFiltered, float torqueLimit, const Eigen::VectorXf &impedanceJointTorque)
Brief description of class CollisionAvoidanceBase.
std::shared_ptr< class Robot > RobotPtr