29 #include <RobotComponents/interface/components/GraspingManager/GraspingManagerInterface.h>
30 #include <RobotComponents/interface/components/GraspingManager/GraspGeneratorInterface.h>
31 #include <RobotComponents/interface/components/GraspingManager/GraspSelectionManagerInterface.h>
32 #include <RobotComponents/interface/components/GraspingManager/RobotPlacementInterface.h>
33 #include <RobotComponents/interface/components/MotionPlanning/MotionPlanningServer.h>
35 #include <RobotComponents/interface/components/PlannedMotionProviderInterface.h>
38 #include <RobotAPI/interface/core/RobotState.h>
39 #include <MemoryX/interface/components/WorkingMemoryInterface.h>
40 #include <MemoryX/interface/components/PriorKnowledgeInterface.h>
41 #include <MemoryX/interface/gui/EntityDrawerInterface.h>
44 #include <Eigen/Geometry>
62 defineOptionalProperty<std::string>(
"GraspGeneratorName",
"SimpleGraspGenerator",
"Name of the GraspGenerator proxy");
63 defineOptionalProperty<std::string>(
"RobotPlacementName",
"SimpleRobotPlacement",
"Name of the RobotPlacement proxy");
64 defineOptionalProperty<std::string>(
"RobotNodeSetNames",
"HipYawRightArm;HipYawLeftArm",
"Names of the robot node sets to use for IK calculations (';' delimited)");
66 defineRequiredProperty<std::string>(
"JointToLinkSetMapping",
"Mapping from joint set to link set, i.e. which collision set to use for which kinematic chain. Format: JointSet1:CollisionSet1;JointSet2:CollisionSet2",
PropertyDefinitionBase::eModifiable);
67 defineOptionalProperty<std::string>(
"ReachabilitySpaceFilePaths",
68 "Armar3/reachability/reachability_right_hand_smoothened.bin;Armar3/reachability/reachability_left_hand_smoothened.bin",
69 "Paths to the reachability space files (needed only if no reachability space is loaded for the chosen RobotNodeSets) (';' delimited)");
70 defineOptionalProperty<std::string>(
"PlanningBoundingBox",
"-15000, -4000, -3.1416, 15000, 15000, 3.1416",
"x_min, y_min, alpha_min, x_max, y_max, alpha_max");
71 defineOptionalProperty<float>(
"VisualizationSlowdownFactor", 1.0f,
"1.0 is a good value for clear visualization, 0 the visualization should not slow down the process",
PropertyDefinitionBase::eModifiable);
73 defineOptionalProperty<float>(
"MaxDistanceForDirectGrasp", 1200.0f,
"x-y-Distance from robot base to object for which the grasping manager tries to find a solution without platform movement",
PropertyDefinitionBase::eModifiable);
76 defineOptionalProperty<bool>(
"FilterUnnaturalGrasps",
false,
"If set to true, uses the NaturalGraspFilter to exclude unnatural looking grasps and grasp poses.",
PropertyDefinitionBase::eModifiable);
112 virtual public GraspingManagerInterface,
121 return "GraspingManager";
135 GraspingTrajectory
generateGraspingTrajectory(
const std::string& objectInstanceEntityId,
const Ice::Current&
c = Ice::emptyCurrent)
override;
138 void visualizeGraspingTrajectory(
const GraspingTrajectory& trajectory,
float visuSlowdownFactor,
const Ice::Current&
c = Ice::emptyCurrent)
override;
140 MotionPlanningDataList
generateIKs(
const std::string& objectInstanceEntityId,
const Ice::Current&
c = Ice::emptyCurrent)
override;
144 GeneratedGraspList
generateGraspsByObjectName(
const std::string& objectName,
const Ice::Current& = Ice::emptyCurrent)
override;
179 std::pair<std::string, Ice::StringSeq>
visualizeGrasp(
const GeneratedGrasp& grasp,
int id,
const DrawColor& color = DrawColor {1, 1, 1, 1});
198 GeneratedGraspList generateGrasps(
const std::string& objectInstanceEntityId);
203 GeneratedGraspList filterGrasps(
const GeneratedGraspList& grasps);
208 GraspingPlacementList filterPlacements(
const GraspingPlacementList& placements);
216 GraspingPlacementList generateRobotPlacements(
const GeneratedGraspList& grasps);
227 GraspingTrajectory planMotion(
const MotionPlanningData& mpd);
233 void drawTrajectory(
const GraspingTrajectory& t,
float visuSlowdownFactor);
245 std::vector<MotionPlanningData> calculateIKs(
const GraspingPlacementList& graspPlacements);
261 NameValueMap calculateSingleIK(const ::std::string& robotNodeSetName,
const std::string& eef,
const PoseBasePtr& globalRobotPose, const ::armarx::FramedPoseBasePtr& tcpPose,
bool checkCollisionFree =
true);
268 armarx::StringStringDictionary getJointSetCollisionSetMapping();
277 GraspingTrajectoryList generateGraspingTrajectoryListForGraspListInternal(
const GeneratedGraspList& grasps);
278 MotionPlanningDataList generateIKsInternal(
const GeneratedGraspList& grasps);
280 std::vector<std::string> getRobotNodeSetNodesWithoutAllwaysColliding(
const std::vector<std::string>& robotColNodeNames,
const std::string& armCollisionSet);
282 void setDescriptionPositionForObject(
const std::string& objId);
283 void setNextStepDescription(
const std::string& description);
284 void resetStepDescription();
285 std::string graspGeneratorName;
286 std::string robotPlacementName;
287 std::vector<std::string> robotNodeSetNames;
288 std::vector<std::string> reachabilitySpaceFilePaths;
290 Vector3fRange planningBoundingBox;
291 GraspGeneratorInterfacePrx gg;
292 GraspSelectionManagerInterfacePrx gsm;
293 GraspSelectionCriterionInterfacePrx gsc;
294 RobotPlacementInterfacePrx rp;
296 PlannedMotionProviderInterfacePrx pmp;
304 memoryx::CommonStorageInterfacePrx cs;
305 memoryx::WorkingMemoryInterfacePrx wm;
306 memoryx::PriorKnowledgeInterfacePrx prior;
308 memoryx::EntityDrawerInterfacePrx entityDrawer;
309 std::string layerName;
310 std::string robotVisuId;
315 std::vector<CSpaceVisualizerTaskHandle> planningTasks;
316 Mutex graspManagerMutex;