CollisionAvoidanceController Class Reference

#include <armarx/control/common/control_law/CollisionAvoidance.h>

Classes

struct  JointRangeBufferZoneData
 
class  RtStatusForSafetyStrategy
 internal status of the controller, containing intermediate variables, mutable targets More...
 
struct  SelfCollisionData
 

Public Types

using Config = common::control_law::arondto::CollisionAvoidanceConfig
 
using DistanceResults = std::vector<::simox::control::environment::DistanceResult >
 
using DistanceResultsPtr = std::shared_ptr< DistanceResults >
 
using FTConfig = common::ft::arondto::FTConfig
 
using InertiaPtr = std::shared_ptr< simox::control::geodesics::metric::Inertia >
 
using SimoxRobotPtr = std::shared_ptr< simox::control::simox::robot::Robot >
 

Public Member Functions

 CollisionAvoidanceController (const VirtualRobot::RobotNodeSetPtr &rtRns)
 
void initialize (SimoxRobotPtr &simoxControlRobot)
 
void preactivateInit (Config &c, RtStatusForSafetyStrategy &rtStatus)
 
void run (Config &c, RtStatusForSafetyStrategy &robotStatus, DistanceResultsPtr &collisionPairs, std::shared_ptr< std::vector< int >> &pointsOnArm, int pointsOnArmIndex, InertiaPtr &inertiaInstance, std::vector< std::string > &selfCollisionNodes, Eigen::VectorXf &qpos, Eigen::VectorXf &qvelFiltered, float torqueLimit)
 ------------------------------— main rt-loop ---------------------------------------— More...
 
 ~CollisionAvoidanceController ()
 

Public Attributes

unsigned int numOfJoints
 
VirtualRobot::RobotNodeSetPtr rtRNS
 

Detailed Description

Definition at line 58 of file CollisionAvoidance.h.

Member Typedef Documentation

◆ Config

using Config = common::control_law::arondto::CollisionAvoidanceConfig

Definition at line 66 of file CollisionAvoidance.h.

◆ DistanceResults

using DistanceResults = std::vector<::simox::control::environment::DistanceResult>

Definition at line 62 of file CollisionAvoidance.h.

◆ DistanceResultsPtr

using DistanceResultsPtr = std::shared_ptr<DistanceResults>

Definition at line 63 of file CollisionAvoidance.h.

◆ FTConfig

using FTConfig = common::ft::arondto::FTConfig

Definition at line 65 of file CollisionAvoidance.h.

◆ InertiaPtr

using InertiaPtr = std::shared_ptr<simox::control::geodesics::metric::Inertia>

Definition at line 61 of file CollisionAvoidance.h.

◆ SimoxRobotPtr

using SimoxRobotPtr = std::shared_ptr<simox::control::simox::robot::Robot>

Definition at line 64 of file CollisionAvoidance.h.

Constructor & Destructor Documentation

◆ CollisionAvoidanceController()

CollisionAvoidanceController ( const VirtualRobot::RobotNodeSetPtr &  rtRns)

Definition at line 14 of file CollisionAvoidance.cpp.

+ Here is the call graph for this function:

◆ ~CollisionAvoidanceController()

Definition at line 22 of file CollisionAvoidance.cpp.

Member Function Documentation

◆ initialize()

void initialize ( SimoxRobotPtr simoxControlRobot)

Definition at line 29 of file CollisionAvoidance.cpp.

◆ preactivateInit()

void preactivateInit ( Config c,
RtStatusForSafetyStrategy rtStatus 
)

◆ run()

void run ( Config c,
RtStatusForSafetyStrategy robotStatus,
DistanceResultsPtr collisionPairs,
std::shared_ptr< std::vector< int >> &  pointsOnArm,
int  pointsOnArmIndex,
InertiaPtr inertiaInstance,
std::vector< std::string > &  selfCollisionNodes,
Eigen::VectorXf &  qpos,
Eigen::VectorXf &  qvelFiltered,
float  torqueLimit 
)

------------------------------— main rt-loop ---------------------------------------—

--------------------------— inertia calculations -----------------------------------------------—

--------------------------— safety constraints -----------------------------------------------—

------------------------— apply EMA low pass filter --------------------------------------------—

filter safety constraint values using EMA low pass filter

assign filtered values

--------------------------— hierarchical control -----------------------------------------------— The following control hierarchies are considered:

three tasks in hierarchy: "enableSelfCollisionAvoidance": true, "enableJointLimitAvoidance": true

flag: "samePriority": true same priority: torque_coll + torque_jl + torque_imp

flag: "topPrioritySelfCollisionAvoidance": true, "samePriority": false self-coll avoidance on top: torque_coll -> torque_jl -> torque_imp

flag: "topPriorityJointLimitAvoidance": true, "samePriority": false joint limit avoidance on top: torque_jl -> torque_coll -> torque_imp

flag: "topPrioritySelfCollisionAvoidance": false, "topPriorityJointLimitAvoidance": false, "samePriority": false (torque_coll + torque_jl) -> torque_imp self-coll and joint limit avoidance on same priority level:

two tasks in hierarchy:

"enableSelfCollisionAvoidance": true, "enableJointLimitAvoidance": false self-coll avoidance on top: torque_coll -> torque_imp

"enableSelfCollisionAvoidance": false, "enableJointLimitAvoidance": true joint limit avoidance on top: torque_jl -> torque_imp

one task in hierarchy (impedance control):

"enableSelfCollisionAvoidance": false, "enableJointLimitAvoidance": false only impedance control: torque_imp

three tasks in hierarchy considered

impedance control and self-collision avoidance

impedance control and joint limit avoidance

plain impedance control

----------------------— write impedance forces to buffer --------------------------------------—

--------------------------— write torque target -----------------------------------------------—

Definition at line 999 of file CollisionAvoidance.cpp.

+ Here is the call graph for this function:

Member Data Documentation

◆ numOfJoints

unsigned int numOfJoints

Definition at line 292 of file CollisionAvoidance.h.

◆ rtRNS

VirtualRobot::RobotNodeSetPtr rtRNS

Definition at line 293 of file CollisionAvoidance.h.


The documentation for this class was generated from the following files: