Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions include/mujincontrollerclient/binpickingtask.h
Original file line number Diff line number Diff line change
Expand Up @@ -234,6 +234,12 @@ class MUJINCLIENT_API BinPickingTaskResource : public TaskResource
{
RuntimeRegistrationInfo();

struct DetectionPointCloudCorner3D
{
std::array<double, 3> cornerPoint; ///< The point in 3D where the corner is located.
std::array<std::array<double, 3>, 2> cornerAxes; ///< Two normalized vectors that describe the axes of the corner in 3D.
};

struct ObjectInfo
{
ObjectInfo();
Expand All @@ -249,6 +255,8 @@ class MUJINCLIENT_API BinPickingTaskResource : public TaskResource
double objectWeight; ///< If non-zero, use this weight fo registration. unit is kg. zero means unknown.
uint64_t sensorTimeStampMS; ///< sensor timestamp of the item. If non-zero, then valid.
uint64_t updateTimeStampMS; ///< timestamp this request was sent. If non-zero, then valid.
std::vector<DetectionPointCloudCorner3D> detectionPointCloudCorners3D; ///< a list of 3D corners in the pointcloud from which the detection was created.

} objectInfo;

struct EndEffectorPoseInfo
Expand Down
12 changes: 12 additions & 0 deletions src/binpickingtask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -624,6 +624,18 @@ void BinPickingTaskResource::ResultGetBinpickingState::Parse(const rapidjson::Va
LoadJsonValueByPath(v, "/runtimeRegistrationInfo/objectInfo/quaternion", runtimeRegistrationInfo.objectInfo.quaternion);
LoadJsonValueByPath(v, "/runtimeRegistrationInfo/objectInfo/translationInEndEffector", runtimeRegistrationInfo.objectInfo.translationInEndEffector);
LoadJsonValueByPath(v, "/runtimeRegistrationInfo/objectInfo/quaternionInEndEffector", runtimeRegistrationInfo.objectInfo.quaternionInEndEffector);
runtimeRegistrationInfo.objectInfo.detectionPointCloudCorners3D.clear();
const rapidjson::Value *pChild = rapidjson::Pointer("/runtimeRegistrationInfo/objectInfo/detectionPointCloudCorners3D").Get(v);
if (!!pChild && !pChild->IsNull()) {
const rapidjson::Value& child = *pChild;
runtimeRegistrationInfo.objectInfo.detectionPointCloudCorners3D.resize(child.Size());
for(int idpcc = 0; idpcc < (int)runtimeRegistrationInfo.objectInfo.detectionPointCloudCorners3D.size(); ++idpcc) {
const rapidjson::Value& result = child[idpcc];
runtimeRegistrationInfo.objectInfo.detectionPointCloudCorners3D[idpcc].cornerPoint = GetJsonValueByKey<std::array<double, 3> >(result, "cornerPoint");
runtimeRegistrationInfo.objectInfo.detectionPointCloudCorners3D[idpcc].cornerAxes = GetJsonValueByKey<std::array<std::array<double, 3>, 2> >(result, "cornerAxes");
}
}

runtimeRegistrationInfo.objectInfo.unit = GetJsonValueByPath<std::string>(v, "/runtimeRegistrationInfo/objectInfo/unit", "mm");
runtimeRegistrationInfo.objectInfo.pickLocationName = GetJsonValueByPath<std::string>(v, "/runtimeRegistrationInfo/objectInfo/pickLocationName", "");
runtimeRegistrationInfo.objectInfo.registrationLocationName = GetJsonValueByPath<std::string>(v, "/runtimeRegistrationInfo/objectInfo/registrationLocationName", "");
Expand Down