25#include <VirtualRobot/MathTools.h>
26#include <VirtualRobot/RobotNodeSet.h>
43#include <simox/control/geodesics/util.h>
44#include <simox/control/robot/NodeInterface.h>
45#include <simox/control/environment/collision.h>
46#include <simox/control/utils/primitive.h>
50#include <boost/shared_ptr.hpp>
54 NJointControllerRegistration<NJointTaskspaceObjectCollisionAvoidanceImpedanceController>
56 "NJointTaskspaceObjectCollisionAvoidanceImpedanceController");
61 const NJointControllerConfigPtr& config,
65 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
67 userCfgWithColl = CollisionCtrlCfg::FromAron(cfg->config);
69 coll = std::make_shared<core::ObjectCollisionAvoidanceBase>(
rtGetRobot(), userCfgWithColl.coll);
70 collReady.store(
true);
77 return "NJointTaskspaceObjectCollisionAvoidanceImpedanceController";
83 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
85 double time_update_status = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
87 arm->controller.run(arm->rtConfig, arm->rtStatus);
88 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
93 coll->rtLimbControllerRun(arm->kinematicChainName,
94 arm->rtStatus.jointPosition,
95 arm->rtStatus.qvelFiltered,
96 arm->rtConfig.torqueLimit,
97 arm->rtStatus.desiredJointTorque);
99 double time_coll_run = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
101 if (collReady.load())
104 coll->collLimb.at(arm->kinematicChainName).rts.desiredJointTorques);
110 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
112 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
114 if (time_measure > 200)
117 "time_update_status: %.2f\n"
118 "run_rt_limb: %.2f\n"
119 "run_coll_rt_limb: %.2f\n"
120 "set_target_limb: %.2f\n"
123 time_run_rt - time_update_status,
124 time_coll_run - time_run_rt,
125 time_set_target - time_coll_run,
127 .deactivateSpam(1.0f);
133 const IceUtil::Time& sensorValuesTimestamp,
134 const IceUtil::Time& timeSinceLastIteration)
136 double deltaT = timeSinceLastIteration.toSecondsDouble();
138 if (collReady.load())
141 coll->updateRtConfigFromUser();
142 coll->updateRtCollisionObjects();
143 coll->rtCollisionChecking();
145 for (
auto& pair :
limb)
147 this->
limbRT(pair.second, deltaT);
151 hands->updateRTStatus(deltaT);
159 Eigen::Matrix3d rotation = transformation.block<3,3>(0,0);
160 Eigen::Vector3d translation = transformation.block<3,1>(0,3);
169 const ::armarx::aron::data::dto::DictPtr& dto,
170 const Ice::Current& iceCurrent)
173 auto cfg = common::control_law::arondto::ObjectCollisionAvoidanceConfigDict::FromAron(dto);
174 coll->setUserCfg(cfg);
180 size_t numCollisionObjects = 0;
182 numCollisionObjects += pair.second.size();
185 std::vector<hpp::fcl::CollisionObject> allCollisionObjects;
186 allCollisionObjects.reserve(numCollisionObjects);
188 allCollisionObjects.insert(allCollisionObjects.end(), pair.second.begin(), pair.second.end());
191 coll->updateUserCollisionObjects(allCollisionObjects);
196 const std::string& primitiveSourceName,
197 const ::armarx::aron::data::dto::DictPtr& dto,
198 const Ice::Current& iceCurrent)
201 auto scene = common::control_law::arondto::CollisionScene::FromAron(dto);
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 =
collisionObjects[primitiveSourceName];
213 collisionObjectsOfSource.clear();
214 collisionObjectsOfSource.reserve(boxes.size() + spheres.size() + cylinders.size() + capsules.size() + ellipsoids.size());
216 for (
auto box : boxes)
218 collisionObjectsOfSource.push_back(
219 simox::control::environment::createCollisionObject(
220 simox::control::utils::primitive::Box{.lengthX = box.lengthX, .lengthY = box.lengthY, .lengthZ = box.lengthZ},
221 matrixToIsometry(box.transformation)
226 for (
auto sphere : spheres)
228 collisionObjectsOfSource.push_back(
229 simox::control::environment::createCollisionObject(
230 simox::control::utils::primitive::Sphere{.radius = sphere.radius},
231 matrixToIsometry(sphere.transformation)
236 for (
auto cylinder : cylinders)
238 collisionObjectsOfSource.push_back(
239 simox::control::environment::createCollisionObject(
240 simox::control::utils::primitive::Cylinder{.radius = cylinder.radius, .lengthY = cylinder.lengthY},
241 matrixToIsometry(cylinder.transformation)
246 for (
auto capsule : capsules)
248 collisionObjectsOfSource.push_back(
249 simox::control::environment::createCollisionObject(
250 simox::control::utils::primitive::Capsule{.radius = capsule.radius, .lengthY = capsule.lengthY},
251 matrixToIsometry(capsule.transformation)
256 for (
auto ellipsoid : ellipsoids)
258 collisionObjectsOfSource.push_back(
259 simox::control::environment::createCollisionObject(
260 simox::control::utils::primitive::Ellipsoid{.lengthX = ellipsoid.lengthX, .lengthY = ellipsoid.lengthY, .lengthZ = ellipsoid.lengthZ},
261 matrixToIsometry(ellipsoid.transformation)
273 const Ice::Current& iceCurrent)
275 if (not collReady.load())
279 return coll->userCfg.toAronDTO();
284 const ::armarx::aron::data::dto::DictPtr& dto,
285 const Ice::Current& iceCurrent)
288 userCfgWithColl = CollisionCtrlCfg::FromAron(dto);
290 coll->setUserCfg(userCfgWithColl.coll);
299 return userCfgWithColl.toAronDTO();
312 datafields[
"trackingError"] =
new Variant(rtStatus.trackingError);
318 datafields,
"projectedImpedanceTorque", rtStatus.projImpedanceJointTorque);
324 Eigen::VectorXf selfCollNullspace = rtStatus.selfCollNullSpace.diagonal();
325 Eigen::VectorXf jointLimNullspace = rtStatus.jointLimNullSpace.diagonal();
360 for (
int i = 0; i < rtStatus.activeCollPairsNum; ++i) {
365 .fromTo(rtStatus.collDataVec[i].point1 * 1000.0,
366 rtStatus.collDataVec[i].point1 * 1000.0 +
367 rtStatus.collDataVec[i].direction * 50.0 *
368 rtStatus.collDataVec[i].repulsiveForce)
369 .
color(simox::Color::blue()));
373 datafields[std::to_string(i) +
"_minDistance"] =
374 new Variant(rtStatus.collDataVec[i].minDistance);
375 datafields[std::to_string(i) +
"_repForce"] =
376 new Variant(rtStatus.collDataVec[i].repulsiveForce);
377 datafields[std::to_string(i) +
"_dampingForce"] =
378 new Variant(-1.0f * rtStatus.collDataVec[i].damping *
379 rtStatus.collDataVec[i].distanceVelocity);
380 datafields[std::to_string(i) +
"_n_des(d)"] =
381 new Variant(rtStatus.collDataVec[i].desiredNSColl);
383 datafields, std::to_string(i) +
"_point", rtStatus.collDataVec[i].point1);
385 datafields, std::to_string(i) +
"_dir", rtStatus.collDataVec[i].direction);
635 .fromTo(rtStatus.globalPose.block<3, 1>(0, 3),
636 rtStatus.globalPose.block<3, 1>(0, 3) +
637 rtStatus.projForceImpedance.head(3) * 1000.0)
638 .
color(simox::Color::red()));
663 debugObs->setDebugChannel(
"CollAvoid_ImpCtrl_" + arm.
nodeSetName, datafields);
668 const std::vector<hpp::fcl::CollisionObject>&
objects,
670 const std::string& layerSuffix)
674 for (
size_t i = 0; i <
objects.size(); ++i)
677 auto position =
object.getTranslation().cast<
float>() * 1000;
678 auto rotation =
object.getRotation().cast<
float>();
680 switch (
object.getNodeType())
682 case hpp::fcl::NODE_TYPE::GEOM_BOX:
684 const hpp::fcl::Box* box = std::static_pointer_cast<hpp::fcl::Box>(
object.collisionGeometry()).get();
686 .
size(box->halfSide.cast<
float>() * 1000 * 2)
689 .
color(255, 0, 0, 128);
690 objectLayer.
add(vizObject);
693 case hpp::fcl::NODE_TYPE::GEOM_SPHERE:
695 const hpp::fcl::Sphere* sphere = std::static_pointer_cast<hpp::fcl::Sphere>(
object.collisionGeometry()).get();
697 .
radius(
static_cast<float>(sphere->radius) * 1000)
700 .
color(0, 0, 255, 128);
701 objectLayer.
add(vizObject);
704 case hpp::fcl::NODE_TYPE::GEOM_CYLINDER:
707 const auto _rotation = rotation * Eigen::AngleAxisf(-
M_PI / 2., Eigen::Vector3f::UnitX());
708 const hpp::fcl::Cylinder* cylinder = std::static_pointer_cast<hpp::fcl::Cylinder>(
object.collisionGeometry()).get();
710 .
height(
static_cast<float>(cylinder->halfLength) * 1000 * 2)
711 .
radius(
static_cast<float>(cylinder->radius) * 1000)
714 .
color(0, 255, 0, 128);
715 objectLayer.
add(vizObject);
718 case hpp::fcl::NODE_TYPE::GEOM_CAPSULE: {
719 const hpp::fcl::Capsule* capsule = std::static_pointer_cast<hpp::fcl::Capsule>(
object.collisionGeometry()).get();
720 Eigen::Vector3f offset;
721 offset << 0, 0, static_cast<float>(capsule->halfLength) * 1000;
722 offset = rotation * offset;
724 .
radius(
static_cast<float>(capsule->radius) * 1000)
727 .
color(255, 200, 0, 128);
729 .
radius(
static_cast<float>(capsule->radius) * 1000)
732 .
color(255, 200, 0, 128);
733 const auto _rotation = rotation * Eigen::AngleAxisf(-
M_PI / 2., Eigen::Vector3f::UnitX());
735 .
height(
static_cast<float>(capsule->halfLength) * 1000 * 2)
736 .
radius(
static_cast<float>(capsule->radius) * 1000)
737 .
color(255, 200, 0, 128)
740 objectLayer.
add(vizObject);
741 objectLayer.
add(cap1);
742 objectLayer.
add(cap2);
745 case hpp::fcl::NODE_TYPE::GEOM_ELLIPSOID:
747 const hpp::fcl::Ellipsoid* ellipsoid = std::static_pointer_cast<hpp::fcl::Ellipsoid>(
object.collisionGeometry()).get();
750 .
axisLengths(ellipsoid->radii.cast<
float>() * 1000)
753 .
color(255, 0, 200, 128);
754 objectLayer.
add(vizObject);
760 arviz.commit(objectLayer);
772 for (
auto& pair :
coll->collLimb)
778 const auto& robotObjects =
coll->collisionRobot->getCollisionManager()->getObjects();
779 std::vector<hpp::fcl::CollisionObject> robotObjectsByValue;
780 for (
const auto* ptr : robotObjects) {
781 robotObjectsByValue.push_back(*ptr);
791 "rt Preactivate controller NJointTaskspaceObjectCollisionAvoidanceImpedanceController");
794 if (collReady.load())
797 coll->rtPreActivate();
805 if (collReady.load())
808 coll->rtPostDeactivate();
811 "post deactivate: NJointTaskspaceObjectCollisionAvoidanceImpedanceController");
817 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
818 const std::map<std::string, ConstSensorDevicePtr>&)
824 ::armarx::WidgetDescription::WidgetSeq widgets;
827 LabelPtr label =
new Label;
828 label->text =
"select a controller config";
830 StringComboBoxPtr cfgBox =
new StringComboBox;
831 cfgBox->name =
"config_box";
832 cfgBox->defaultIndex = 0;
833 cfgBox->multiSelect =
false;
835 cfgBox->options = std::vector<std::string>{
836 "default",
"default_a7_right",
"default_a7_right_zero_torque"};
839 layout->children.emplace_back(label);
840 layout->children.emplace_back(cfgBox);
843 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
852 auto cfgName = values.at(
"config_box")->getString();
855 "controller_config/NJointTaskspaceObjectCollisionAvoidanceImpedanceController/" + cfgName +
863 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
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 onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
std::map< std::string, ArmPtr > limb
void limbRTSetTarget(ArmPtr &arm, const Eigen::VectorXf &targetTorque)
NJointTaskspaceImpedanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
core::HandControlPtr hands
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
std::unique_ptr< ArmData > ArmPtr
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
void rtPreActivateController() override
This function is called before the controller is activated.
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
void collObjectPublish(const std::vector< hpp::fcl::CollisionObject > &objects, const DebugObserverInterfacePrx &debugObs, const std::string &layerSuffix)
static WidgetDescription::WidgetPtr GenerateConfigDescription(const VirtualRobot::RobotPtr &, const std::map< std::string, ConstControlDevicePtr > &, const std::map< std::string, ConstSensorDevicePtr > &)
ConfigurableNJointControllerConfigPtr ConfigPtrT
void limbRT(ArmPtr &arm, const double deltaT)
core::ObjectCollisionAvoidanceBasePtr coll
void sendCollisionObjects()
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
std::map< std::string, std::vector< hpp::fcl::CollisionObject > > collisionObjects
NJointTaskspaceObjectCollisionAvoidanceImpedanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
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
TODO make protected and use attorneys.
void updateCollisionObjects(const std::string &primitiveSourceName, const ::armarx::aron::data::dto::DictPtr &scene, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void onPublish(const SensorAndControl &sc, const DebugDrawerInterfacePrx &drawer, const DebugObserverInterfacePrx &) override
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent) override
void collLimbPublish(core::ObjectCollisionAvoidanceBase::NodeSetData &arm, const DebugObserverInterfacePrx &debugObs)
void rtPreActivateController() override
NJointControllerBase interface.
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent) override
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.
#define ARMARX_INFO
The normal logging level.
armarx::aron::data::dto::Dict getCollisionAvoidanceConfig()
std::shared_ptr< class Robot > RobotPtr
::IceInternal::Handle< Dict > DictPtr
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
NJointControllerRegistration< NJointTaskspaceObjectCollisionAvoidanceImpedanceController > registrationControllerNJointTaskspaceObjectCollisionAvoidanceImpedanceController("NJointTaskspaceObjectCollisionAvoidanceImpedanceController")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
AronDTO readFromJson(const std::filesystem::path &filename)
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
IceUtil::Handle< class RobotUnit > RobotUnitPtr
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
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)