25#include <boost/shared_ptr.hpp>
27#include <SimoxUtility/color/Color.h>
28#include <VirtualRobot/MathTools.h>
29#include <VirtualRobot/RobotNodeSet.h>
31#include <simox/control/environment/collision.h>
32#include <simox/control/geodesics/util.h>
33#include <simox/control/robot/NodeInterface.h>
34#include <simox/control/utils/primitive.h>
47#include <armarx/control/common/control_law/aron/CollisionPrimitives.aron.generated.h>
52 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
55 const NJointControllerConfigPtr& config,
57 NJointControllerType{robotUnit, config, robot}
59 auto cfg = ConfigPtrT::dynamicCast(config);
61 userCfgWithColl_ = CollisionCtrlCfg::FromAron(cfg->config);
63 std::map<std::string, std::vector<size_t>> velCtrlIndices;
64 for (
auto& arm : this->
limb)
66 velCtrlIndices.emplace(arm.first, arm.second->rtStatus.jointIDVelocityMode);
68 coll = std::make_shared<CollAvoidBase>(
69 this->rtGetRobot(), userCfgWithColl_.coll, velCtrlIndices);
70 collReady_.store(
true);
75 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
79 arm->controller.run(arm->rtConfig, arm->rtStatus);
81 if (collReady_.load())
88 coll->rtLimbControllerRun(arm->kinematicChainName,
89 arm->rtConfig.torqueLimit,
90 arm->rtConfig.velocityLimit,
114 arm->rtStatus.nDoFTorque,
115 arm->rtStatus.nDoFVelocity,
116 arm->rtStatus.desiredJointTorque,
117 arm->rtStatus.desiredJointVelocity);
120 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
123 const IceUtil::Time& ,
124 const IceUtil::Time& timeSinceLastIteration)
126 double deltaT = timeSinceLastIteration.toSecondsDouble();
129 if (collReady_.load())
132 coll->updateRtConfigFromUser();
133 coll->updateRtCollisionObjects();
134 coll->rtCollisionChecking();
136 for (
auto& pair : this->limb)
138 this->limbRTUpdateStatus(pair.second, deltaT);
141 this->rtRunCoordinator(deltaT);
143 for (
auto& pair : this->limb)
149 this->hands->updateRTStatus(deltaT);
153 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
156 const ::armarx::aron::data::dto::DictPtr& dto,
157 const Ice::Current& )
160 auto cfg = common::control_law::arondto::ObjectCollisionAvoidanceConfigDict::FromAron(dto);
161 coll->setUserCfg(cfg);
164 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
168 size_t numCollisionObjects = 0;
171 numCollisionObjects += pair.second.size();
174 std::vector<hpp::fcl::CollisionObject> allCollisionObjects;
175 allCollisionObjects.reserve(numCollisionObjects);
178 allCollisionObjects.insert(
179 allCollisionObjects.end(), pair.second.begin(), pair.second.end());
182 coll->updateUserCollisionObjects(allCollisionObjects);
185 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
188 const Ice::Current& )
190 coll->deleteUserCollisionObjects();
193 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
196 const std::string& primitiveSourceName,
197 const ::armarx::aron::data::dto::DictPtr& dtoScene,
198 const Ice::Current& )
201 auto scene = common::control_law::arondto::CollisionScene::FromAron(dtoScene);
202 auto boxes = scene.boxes;
203 auto spheres = scene.spheres;
204 auto cylinders = scene.cylinders;
205 auto capsules = scene.capsules;
206 auto ellipsoids = scene.ellipsoids;
210 collisionObjects.emplace(primitiveSourceName, std::vector<hpp::fcl::CollisionObject>());
212 std::vector<hpp::fcl::CollisionObject>& collisionObjectsOfSource =
214 collisionObjectsOfSource.clear();
215 collisionObjectsOfSource.reserve(boxes.size() + spheres.size() + cylinders.size() +
216 capsules.size() + ellipsoids.size());
218 for (
const auto& box : boxes)
220 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
221 simox::control::utils::primitive::Box{
222 .lengthX = box.lengthX, .lengthY = box.lengthY, .lengthZ = box.lengthZ},
223 Eigen::Isometry3d{box.transformation}));
226 for (
const auto& sphere : spheres)
228 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
229 simox::control::utils::primitive::Sphere{.radius = sphere.radius},
230 Eigen::Isometry3d{sphere.transformation}));
233 for (
const auto& cylinder : cylinders)
235 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
236 simox::control::utils::primitive::Cylinder{.radius = cylinder.radius,
237 .lengthY = cylinder.lengthY},
238 Eigen::Isometry3d{cylinder.transformation}));
241 for (
const auto& capsule : capsules)
243 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
244 simox::control::utils::primitive::Capsule{.radius = capsule.radius,
245 .lengthY = capsule.lengthY},
246 Eigen::Isometry3d{capsule.transformation}));
249 for (
const auto& ellipsoid : ellipsoids)
251 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
252 simox::control::utils::primitive::Ellipsoid{.lengthX = ellipsoid.lengthX,
253 .lengthY = ellipsoid.lengthY,
254 .lengthZ = ellipsoid.lengthZ},
255 Eigen::Isometry3d{ellipsoid.transformation}));
261 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
264 const Ice::Current& )
266 if (not collReady_.load())
272 return coll->userCfg.toAronDTO();
275 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
278 const ::armarx::aron::data::dto::DictPtr& dto,
279 const Ice::Current& )
281 NJointControllerType::updateConfig(dto);
282 userCfgWithColl_ = CollisionCtrlCfg::FromAron(dto);
284 coll->setUserCfg(userCfgWithColl_.coll);
287 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
290 const Ice::Current& )
297 NJointControllerType::getConfig();
298 userCfgWithColl_.limbs = this->userConfig.limbs;
299 userCfgWithColl_.hands = this->userConfig.hands;
300 return userCfgWithColl_.toAronDTO();
303 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
310 NJointControllerType::onPublish(sc, drawer, debugObs);
313 for (
auto& pair :
coll->collLimb)
320 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
332 datafields[
"collDistanceThreshold"] =
new Variant(recoveryState.collDistanceThreshold);
333 datafields[
"collDistanceThresholdInit"] =
334 new Variant(recoveryState.collDistanceThresholdInit);
336 datafields[
"trackingError"] =
new Variant(rtStatus.trackingError);
341 datafields[
"selfColAdmInterface.active"] =
342 new Variant(
static_cast<float>(rtStatus.selfColAdmInterface.active));
344 datafields,
"selfColAdmInterface.jointVel", rtStatus.selfColAdmInterface.jointVel);
345 datafields[
"selfColAdmInterface.nDoFVel"] =
346 new Variant(
static_cast<float>(rtStatus.selfColAdmInterface.nDoFVel));
349 datafields[
"jointLimAdmInterface.active"] =
350 new Variant(
static_cast<float>(rtStatus.jointLimAdmInterface.active));
352 datafields,
"jointLimAdmInterface.jointVel", rtStatus.jointLimAdmInterface.jointVel);
353 datafields[
"jointLimAdmInterface.nDoFVel"] =
354 new Variant(
static_cast<float>(rtStatus.jointLimAdmInterface.nDoFVel));
357 datafields,
"projectedImpedanceTorque", rtStatus.projImpedanceJointTorque);
363 const Eigen::VectorXf selfCollNullspace = rtStatus.selfCollNullSpace.diagonal();
364 const Eigen::VectorXf jointLimNullspace = rtStatus.jointLimNullSpace.diagonal();
387 datafields[
"collisionPairsNum"] =
new Variant(rtStatus.collisionPairsNum);
388 datafields[
"activeCollPairsNum"] =
new Variant(rtStatus.activeCollPairsNum);
390 datafields[
"collisionPairTime"] =
new Variant(rtStatus.collisionPairTime);
391 datafields[
"collisionTorqueTime"] =
new Variant(rtStatus.collisionTorqueTime);
392 datafields[
"jointLimitTorqueTime"] =
new Variant(rtStatus.jointLimitTorqueTime);
393 datafields[
"selfCollNullspaceTime"] =
new Variant(rtStatus.selfCollNullspaceTime);
394 datafields[
"jointLimitNullspaceTime"] =
new Variant(rtStatus.jointLimitNullspaceTime);
396 datafields[
"impForceRatio"] =
new Variant(rtStatus.impForceRatio);
397 datafields[
"impTorqueRatio"] =
new Variant(rtStatus.impTorqueRatio);
399 for (
unsigned int i = 0; i < rtStatus.activeCollPairsNum; ++i)
402 datafields[std::to_string(i) +
"_minDistance"] =
403 new Variant(rtStatus.collDataVec[i].minDistance);
404 datafields[std::to_string(i) +
"_repForce"] =
405 new Variant(rtStatus.collDataVec[i].repulsiveForce);
406 datafields[std::to_string(i) +
"_dampingForce"] =
new Variant(
407 -1.0f * rtStatus.collDataVec[i].damping * rtStatus.collDataVec[i].distanceVelocity);
408 datafields[std::to_string(i) +
"_n_des(d)"] =
409 new Variant(rtStatus.collDataVec[i].desiredNSColl);
411 datafields, std::to_string(i) +
"_point", rtStatus.collDataVec[i].point1);
413 datafields, std::to_string(i) +
"_dir", rtStatus.collDataVec[i].direction);
681 debugObs->setDebugChannel(
"CollAvoid_ImpCtrl_" + arm.
nodeSetName, datafields);
684 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
688 const std::vector<hpp::fcl::CollisionObject>&
objects)
690 for (
size_t i = 0; i <
objects.size(); ++i)
693 const auto position =
object.getTranslation().cast<
float>() * 1000;
694 const Eigen::Matrix3f rotation =
object.getRotation().cast<
float>();
696 switch (
object.getNodeType())
698 case hpp::fcl::NODE_TYPE::GEOM_BOX:
700 const hpp::fcl::Box* box =
701 std::static_pointer_cast<hpp::fcl::Box>(
object.collisionGeometry()).get();
703 .
size(box->halfSide.cast<
float>() * 1000 * 2)
706 .
color(255, 0, 0, 128);
707 layer.
add(vizObject);
710 case hpp::fcl::NODE_TYPE::GEOM_SPHERE:
712 const hpp::fcl::Sphere* sphere =
713 std::static_pointer_cast<hpp::fcl::Sphere>(
object.collisionGeometry())
717 .
radius(
static_cast<float>(sphere->radius) * 1000)
720 .
color(0, 0, 255, 128);
721 layer.
add(vizObject);
724 case hpp::fcl::NODE_TYPE::GEOM_CYLINDER:
726 const hpp::fcl::Cylinder* cylinder =
727 std::static_pointer_cast<hpp::fcl::Cylinder>(
object.collisionGeometry())
731 .
height(
static_cast<float>(cylinder->halfLength) * 1000 * 2)
732 .
radius(
static_cast<float>(cylinder->radius) * 1000)
734 Eigen::AngleAxisf(
M_PI / 2., Eigen::Vector3f::UnitX()))
736 .
color(0, 255, 0, 128);
737 layer.
add(vizObject);
740 case hpp::fcl::NODE_TYPE::GEOM_CAPSULE:
742 const hpp::fcl::Capsule* capsule =
743 std::static_pointer_cast<hpp::fcl::Capsule>(
object.collisionGeometry())
745 const auto _rotation =
746 rotation * Eigen::AngleAxisf(
M_PI / 2., Eigen::Vector3f::UnitX());
747 Eigen::Vector3f offset;
748 offset << 0, static_cast<float>(capsule->halfLength) * 1000, 0;
749 offset = _rotation * offset;
752 .
radius(
static_cast<float>(capsule->radius) * 1000)
755 .
color(255, 200, 0, 128);
757 .
radius(
static_cast<float>(capsule->radius) * 1000)
760 .
color(255, 200, 0, 128);
763 .
height(
static_cast<float>(capsule->halfLength) * 1000 * 2)
764 .
radius(
static_cast<float>(capsule->radius) * 1000)
765 .
color(255, 200, 0, 128)
768 layer.
add(vizObject);
773 case hpp::fcl::NODE_TYPE::GEOM_ELLIPSOID:
775 const hpp::fcl::Ellipsoid* ellipsoid =
776 std::static_pointer_cast<hpp::fcl::Ellipsoid>(
object.collisionGeometry())
781 .
axisLengths(ellipsoid->radii.cast<
float>() * 1000)
784 .
color(255, 0, 200, 128);
785 layer.
add(vizObject);
793 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
798 NJointControllerType::collectArviz(stage);
800 auto transformVector = [](
const Eigen::Matrix4f& pose,
801 const Eigen::Vector3f& vec) -> Eigen::Vector3f
806 for (
const auto& [_, arm] :
coll->collLimb)
808 const auto& rtStatus = arm.bufferRTtoPublish.getUpToDateReadBuffer();
810 viz::Layer layer = this->scopedArviz->layer(
"ColStatus_" + arm.nodeSetName);
812 for (
unsigned int i = 0; i < rtStatus.activeCollPairsNum; ++i)
832 .fromTo(transformVector(rtStatus.globalPose,
833 rtStatus.collDataVec[i].point1 * 1000.0F),
834 transformVector(rtStatus.globalPose,
835 rtStatus.collDataVec[i].point1 * 1000.0F +
836 rtStatus.collDataVec[i].direction * 50.0F *
837 rtStatus.collDataVec[i].repulsiveForce))
838 .
color(simox::Color::blue())
861 if (not
coll->userCollisionObjects.empty())
863 viz::Layer layer = this->scopedArviz->layer(
"ColStatus_objectModels");
867 const bool enableRobotPrimitiveVis =
true;
868 if (enableRobotPrimitiveVis)
871 const auto& robotObjects =
872 coll->collisionRobot->getCollisionManager()->getObjects();
873 std::vector<hpp::fcl::CollisionObject> robotObjectsByValue;
874 robotObjectsByValue.reserve(robotObjects.size());
875 for (
const auto* ptr : robotObjects)
877 robotObjectsByValue.push_back(*ptr);
879 viz::Layer layer = this->scopedArviz->layer(
"ColStatus_robotModel");
886 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
892 NJointControllerType::rtPreActivateController();
894 if (collReady_.load())
897 coll->rtPreActivate();
901 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
905 NJointControllerType::rtPostDeactivateController();
906 if (collReady_.load())
909 coll->rtPostDeactivate();
915 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
920 auto cfgName = values.at(
"config_box")->getString();
923 "controller_config/" + std::string(NJointControllerType::ControlType::TypeName) +
924 "Col/" + cfgName +
".json");
931 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
936 law::arondto::TSMixImpVelColConfigDict>;
943 const NJointControllerConfigPtr& config,
956 return "TSMixImpVelCol";
967 const NJointControllerConfigPtr& config,
990 const NJointControllerConfigPtr& config,
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
const T & getUpToDateReadBuffer() const
The Variant class is described here: Variants.
void collectArviz(viz::StagedCommit &stage) const override
void sendCollisionObjects()
NJointTSColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
std::map< std::string, std::vector< hpp::fcl::CollisionObject > > collisionObjects
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
static void AddArvizObjects(viz::Layer &layer, const std::vector< hpp::fcl::CollisionObject > &objects)
void rtPostDeactivateController() override
void collLimbPublish(CollAvoidBase::NodeSetData &arm, const DebugObserverInterfacePrx &debugObs)
void updateCollisionAvoidanceConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface for collision avoidance.
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
typename NJointControllerType::ConfigPtrT ConfigPtrT
void onPublish(const SensorAndControl &sc, const DebugDrawerInterfacePrx &drawer, const DebugObserverInterfacePrx &) override
typename NJointControllerType::ArmPtr ArmPtr
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent) override
void updateCollisionObjects(const std::string &primitiveSourceName, const ::armarx::aron::data::dto::DictPtr &dtoScene, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void rtPreActivateController() override
NJointControllerBase interface.
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent) override
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
NJointTSImpColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
NJointTSMixImpVelColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
NJointTSVeloColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
std::map< std::string, ArmPtr > limb
void limbRTSetTarget(ArmPtr &arm, const size_t nDoFTorque, const size_t nDoFVelocity, const Eigen::VectorXf &targetTorque, const Eigen::VectorXf &targetVelocity)
DerivedT & color(Color color)
DerivedT & position(float x, float y, float z)
DerivedT & orientation(Eigen::Quaternionf const &ori)
DerivedT & scale(Eigen::Vector3f scale)
#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.
armarx::aron::data::dto::Dict getCollisionAvoidanceConfig()
void deleteCollisionObjects()
std::shared_ptr< class Robot > RobotPtr
::IceInternal::Handle< Dict > DictPtr
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri(Eigen::Matrix4f &matrix)
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
NJointControllerRegistration< NJointTSVeloColController > registrationControllerNJointTSVeloColController("TSVeloCol")
NJointControllerRegistration< NJointTSMixImpVelColController > registrationControllerNJointTSMixImpVelColController("TSMixImpVelCol")
NJointControllerRegistration< NJointTSImpColController > registrationControllerNJointTSImpColController("TSImpCol")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
AronDTO readFromJson(const std::filesystem::path &filename)
IceUtil::Handle< class RobotUnit > RobotUnitPtr
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
armarx::TripleBuffer< RecoveryState > bufferRecoveryStateSelfColl
armarx::TripleBuffer< RtStatus > bufferRTtoPublish
Box & size(Eigen::Vector3f const &s)
Cylinder & height(float h)
Cylinder & radius(float r)
Ellipsoid & axisLengths(const Eigen::Vector3f &axisLengths)
void add(ElementT const &element)
A staged commit prepares multiple layers to be committed.
void add(Layer const &layer)
Stage a layer to be committed later via client.apply(*this)