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 coll = std::make_shared<CollAvoidVelBase>(this->
rtGetRobot(), userCfgWithColl.coll);
64 collReady.store(
true);
69 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
77 arm->controller.run(arm->rtConfig, arm->rtStatus);
87 coll->rtLimbControllerRun(arm->kinematicChainName,
88 arm->rtStatus.jointPosition,
89 arm->rtStatus.qvelFiltered,
90 arm->rtConfig.velocityLimit,
91 arm->rtStatus.desiredJointVelocity,
94 arm->rtStatus.inertia =
coll->collLimb.at(arm->kinematicChainName).rts.inertia;
100 arm->rtStatus.nDoFTorque,
101 arm->rtStatus.nDoFVelocity,
102 arm->rtStatus.desiredJointTorque,
103 coll->collLimb.at(arm->kinematicChainName).rts.desiredJointVel);
107 this->limbRTSetTarget(arm,
108 arm->rtStatus.nDoFTorque,
109 arm->rtStatus.nDoFVelocity,
110 arm->rtStatus.desiredJointTorque,
111 arm->rtStatus.desiredJointVelocity);
115 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
118 const IceUtil::Time& sensorValuesTimestamp,
119 const IceUtil::Time& timeSinceLastIteration)
121 double deltaT = timeSinceLastIteration.toSecondsDouble();
124 if (collReady.load())
127 coll->updateRtConfigFromUser();
128 coll->updateRtCollisionObjects();
129 coll->rtCollisionChecking();
131 for (
auto& pair : this->limb)
133 this->limbRTUpdateStatus(pair.second, deltaT);
136 this->rtRunCoordinator(deltaT);
138 for (
auto& pair : this->limb)
140 limbRT(pair.second, deltaT);
144 this->hands->updateRTStatus(deltaT);
148 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
152 const Ice::Current& iceCurrent)
156 common::control_law::arondto::ObjectCollisionAvoidanceVelConfigDict::FromAron(dto);
157 coll->setUserCfg(cfg);
160 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
164 size_t numCollisionObjects = 0;
167 numCollisionObjects += pair.second.size();
170 std::vector<hpp::fcl::CollisionObject> allCollisionObjects;
171 allCollisionObjects.reserve(numCollisionObjects);
174 allCollisionObjects.insert(
175 allCollisionObjects.end(), pair.second.begin(), pair.second.end());
178 coll->updateUserCollisionObjects(allCollisionObjects);
181 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
184 const Ice::Current& iceCurrent)
186 coll->deleteUserCollisionObjects();
189 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
192 const std::string& primitiveSourceName,
193 const ::armarx::aron::data::dto::DictPtr& dto,
194 const Ice::Current& iceCurrent)
197 auto scene = common::control_law::arondto::CollisionScene::FromAron(dto);
198 auto boxes = scene.boxes;
199 auto spheres = scene.spheres;
200 auto cylinders = scene.cylinders;
201 auto capsules = scene.capsules;
202 auto ellipsoids = scene.ellipsoids;
206 collisionObjects.emplace(primitiveSourceName, std::vector<hpp::fcl::CollisionObject>());
208 std::vector<hpp::fcl::CollisionObject>& collisionObjectsOfSource =
210 collisionObjectsOfSource.clear();
211 collisionObjectsOfSource.reserve(boxes.size() + spheres.size() + cylinders.size() +
212 capsules.size() + ellipsoids.size());
214 for (
auto box : boxes)
216 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
217 simox::control::utils::primitive::Box{
218 .lengthX = box.lengthX, .lengthY = box.lengthY, .lengthZ = box.lengthZ},
219 Eigen::Isometry3d{box.transformation}));
222 for (
auto sphere : spheres)
224 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
225 simox::control::utils::primitive::Sphere{.radius = sphere.radius},
226 Eigen::Isometry3d{sphere.transformation}));
229 for (
auto cylinder : cylinders)
231 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
232 simox::control::utils::primitive::Cylinder{.radius = cylinder.radius,
233 .lengthY = cylinder.lengthY},
234 Eigen::Isometry3d{cylinder.transformation}));
237 for (
auto capsule : capsules)
239 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
240 simox::control::utils::primitive::Capsule{.radius = capsule.radius,
241 .lengthY = capsule.lengthY},
242 Eigen::Isometry3d{capsule.transformation}));
245 for (
auto ellipsoid : ellipsoids)
247 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
248 simox::control::utils::primitive::Ellipsoid{.lengthX = ellipsoid.lengthX,
249 .lengthY = ellipsoid.lengthY,
250 .lengthZ = ellipsoid.lengthZ},
251 Eigen::Isometry3d{ellipsoid.transformation}));
257 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
262 if (not collReady.load())
266 return coll->userCfg.toAronDTO();
269 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
272 const ::armarx::aron::data::dto::DictPtr& dto,
273 const Ice::Current& iceCurrent)
275 NJointControllerType::updateConfig(dto);
276 userCfgWithColl = CollisionCtrlCfg::FromAron(dto);
278 coll->setUserCfg(userCfgWithColl.coll);
281 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
284 const Ice::Current& iceCurrent)
291 NJointControllerType::getConfig();
292 userCfgWithColl.limbs = this->userConfig.limbs;
293 userCfgWithColl.hands = this->userConfig.hands;
294 return userCfgWithColl.toAronDTO();
297 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
309 datafields[
"collDistanceThreshold"] =
new Variant(recoveryState.collDistanceThreshold);
310 datafields[
"collDistanceThresholdInit"] =
311 new Variant(recoveryState.collDistanceThresholdInit);
313 datafields[
"trackingError"] =
new Variant(rtStatus.trackingError);
325 const Eigen::VectorXf selfCollNullspace = rtStatus.selfCollNullSpace.diagonal();
326 const Eigen::VectorXf jointLimNullspace = rtStatus.jointLimNullSpace.diagonal();
349 datafields[
"collisionPairsNum"] =
new Variant(rtStatus.collisionPairsNum);
350 datafields[
"activeCollPairsNum"] =
new Variant(rtStatus.activeCollPairsNum);
352 datafields[
"collisionPairTime"] =
new Variant(rtStatus.collisionPairTime);
353 datafields[
"collisionTorqueTime"] =
new Variant(rtStatus.collisionTorqueTime);
354 datafields[
"jointLimitTorqueTime"] =
new Variant(rtStatus.jointLimitTorqueTime);
355 datafields[
"selfCollNullspaceTime"] =
new Variant(rtStatus.selfCollNullspaceTime);
356 datafields[
"jointLimitNullspaceTime"] =
new Variant(rtStatus.jointLimitNullspaceTime);
358 datafields[
"impForceRatio"] =
new Variant(rtStatus.impForceRatio);
359 datafields[
"impTorqueRatio"] =
new Variant(rtStatus.impTorqueRatio);
375 for (
unsigned int i = 0; i < rtStatus.activeCollPairsNum; ++i)
404 datafields[std::to_string(i) +
"_minDistance"] =
405 new Variant(rtStatus.collDataVec[i].minDistance);
406 datafields[std::to_string(i) +
"_repVel"] =
407 new Variant(rtStatus.collDataVec[i].repulsiveVel);
408 datafields[std::to_string(i) +
"_dampingForce"] =
new Variant(
409 -1.0f * rtStatus.collDataVec[i].damping * rtStatus.collDataVec[i].distanceVelocity);
410 datafields[std::to_string(i) +
"_n_des(d)"] =
411 new Variant(rtStatus.collDataVec[i].desiredNSColl);
413 datafields, std::to_string(i) +
"_point", rtStatus.collDataVec[i].point1);
415 datafields, std::to_string(i) +
"_dir", rtStatus.collDataVec[i].direction);
700 debugObs->setDebugChannel(
"CollAvoid_ImpCtrl_" + arm.
nodeSetName, datafields);
703 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
706 const std::vector<hpp::fcl::CollisionObject>&
objects,
708 const std::string& layerSuffix)
712 for (
size_t i = 0; i <
objects.size(); ++i)
715 const auto position =
object.getTranslation().cast<
float>() * 1000;
716 const Eigen::Matrix3f rotation =
object.getRotation().cast<
float>();
718 switch (
object.getNodeType())
720 case hpp::fcl::NODE_TYPE::GEOM_BOX:
722 const hpp::fcl::Box* box =
723 std::static_pointer_cast<hpp::fcl::Box>(
object.collisionGeometry()).get();
725 .
size(box->halfSide.cast<
float>() * 1000 * 2)
728 .
color(255, 0, 0, 128);
729 objectLayer.
add(vizObject);
732 case hpp::fcl::NODE_TYPE::GEOM_SPHERE:
734 const hpp::fcl::Sphere* sphere =
735 std::static_pointer_cast<hpp::fcl::Sphere>(
object.collisionGeometry())
739 .
radius(
static_cast<float>(sphere->radius) * 1000)
742 .
color(0, 0, 255, 128);
743 objectLayer.
add(vizObject);
746 case hpp::fcl::NODE_TYPE::GEOM_CYLINDER:
748 const hpp::fcl::Cylinder* cylinder =
749 std::static_pointer_cast<hpp::fcl::Cylinder>(
object.collisionGeometry())
753 .
height(
static_cast<float>(cylinder->halfLength) * 1000 * 2)
754 .
radius(
static_cast<float>(cylinder->radius) * 1000)
756 Eigen::AngleAxisf(
M_PI / 2., Eigen::Vector3f::UnitX()))
758 .
color(0, 255, 0, 128);
759 objectLayer.
add(vizObject);
762 case hpp::fcl::NODE_TYPE::GEOM_CAPSULE:
764 const hpp::fcl::Capsule* capsule =
765 std::static_pointer_cast<hpp::fcl::Capsule>(
object.collisionGeometry())
767 const auto _rotation =
768 rotation * Eigen::AngleAxisf(
M_PI / 2., Eigen::Vector3f::UnitX());
769 Eigen::Vector3f offset;
770 offset << 0, static_cast<float>(capsule->halfLength) * 1000, 0;
771 offset = _rotation * offset;
774 .
radius(
static_cast<float>(capsule->radius) * 1000)
777 .
color(255, 200, 0, 128);
779 .
radius(
static_cast<float>(capsule->radius) * 1000)
782 .
color(255, 200, 0, 128);
785 .
height(
static_cast<float>(capsule->halfLength) * 1000 * 2)
786 .
radius(
static_cast<float>(capsule->radius) * 1000)
787 .
color(255, 200, 0, 128)
790 objectLayer.
add(vizObject);
791 objectLayer.
add(cap1);
792 objectLayer.
add(cap2);
795 case hpp::fcl::NODE_TYPE::GEOM_ELLIPSOID:
797 const hpp::fcl::Ellipsoid* ellipsoid =
798 std::static_pointer_cast<hpp::fcl::Ellipsoid>(
object.collisionGeometry())
803 .
axisLengths(ellipsoid->radii.cast<
float>() * 1000)
806 .
color(255, 0, 200, 128);
807 objectLayer.
add(vizObject);
813 arviz.commit(objectLayer);
816 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
823 NJointControllerType::onPublish(sc, drawer, debugObs);
826 for (
auto& pair :
coll->collLimb)
833 const auto& robotObjects =
coll->collisionRobot->getCollisionManager()->getObjects();
834 std::vector<hpp::fcl::CollisionObject> robotObjectsByValue;
835 for (
const auto* ptr : robotObjects)
837 robotObjectsByValue.push_back(*ptr);
843 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
849 NJointControllerType::rtPreActivateController();
851 if (collReady.load())
854 coll->rtPreActivate();
858 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
863 NJointControllerType::rtPostDeactivateController();
864 if (collReady.load())
867 coll->rtPostDeactivate();
873 template <
typename NJo
intControllerType,
typename CollisionCtrlCfg>
878 auto cfgName = values.at(
"config_box")->getString();
881 "controller_config/" + std::string(NJointControllerType::ControlType::TypeName) +
882 "Col/" + cfgName +
".json");
889 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
894 law::arondto::TSVelColConfigDict>;
900 const NJointControllerConfigPtr& config,
armarx::viz::Client arviz
std::string getName() const
Retrieve name of object.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
const T & getUpToDateReadBuffer() const
The Variant class is described here: Variants.
void collObjectPublish(const std::vector< hpp::fcl::CollisionObject > &objects, const DebugObserverInterfacePrx &debugObs, const std::string &layerSuffix)
void collLimbPublish(CollAvoidVelBase::NodeSetData &arm, const DebugObserverInterfacePrx &debugObs)
void limbRT(ArmPtr &arm, const double deltaT)
void sendCollisionObjects()
std::map< std::string, std::vector< hpp::fcl::CollisionObject > > collisionObjects
void rtPostDeactivateController() override
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
void updateCollisionObjects(const std::string &primitiveSourceName, const ::armarx::aron::data::dto::DictPtr &scene, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
typename NJointControllerType::ConfigPtrT ConfigPtrT
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
void onPublish(const SensorAndControl &sc, const DebugDrawerInterfacePrx &drawer, const DebugObserverInterfacePrx &) override
typename NJointTSVelController::ArmPtr ArmPtr
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent) override
NJointTSVelBasedColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
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
NJointTSVelColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
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)
#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)
NJointControllerRegistration< NJointTSVelColController > registrationControllerNJointTSVelColController("TSVelCol")
::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)