#include "Behaviors/Demos/Navigation/PilotDemo.h"

#define PI (3.14159265)
#define FOODX (780+300+300-390)
#define FOODY (400)
#define FOODA (PI/2)
#define HAND WristRotateOffset

$nodeclass GetSnack: PilotDemo {
    
    virtual void buildMap() {
        //April Tags
		NEW_SHAPE(tag1, AprilTagData,new AprilTagData(worldShS, Point(0-390+2750-294-15,0-400+30/2+1,177.8), AprilTags::TagDetection(1) ));
		NEW_SHAPE(tag3, AprilTagData,new AprilTagData(worldShS, Point(0-390+147+15,0-400+30/2+1,177.8), AprilTags::TagDetection(3) ));
		NEW_SHAPE(tag2, AprilTagData,new AprilTagData(worldShS, Point(0-390+2750/2,0-400+30/2+1,177.8), AprilTags::TagDetection(2) ));
		NEW_SHAPE(tag0, AprilTagData,new AprilTagData(worldShS, Point(0-390+2750-15-0.5,0-400+367,177.8), AprilTags::TagDetection(0) ));
		NEW_SHAPE(tag4, AprilTagData,new AprilTagData(worldShS, Point(0-390+15+0.5,0-400+367,177.8), AprilTags::TagDetection(4) ));
		NEW_SHAPE(tag12, AprilTagData,new AprilTagData(worldShS, Point(0-390+780+300/2,800-400-15,177.8), AprilTags::TagDetection(12) ));
		NEW_SHAPE(tag17, AprilTagData,new AprilTagData(worldShS, Point(0-390+780+300+600+390/2,800-400-15,177.8), AprilTags::TagDetection(17) ));
		NEW_SHAPE(tag18, AprilTagData,new AprilTagData(worldShS, Point(0-390+780+300+600/2,1700-400-15+80,177.8), AprilTags::TagDetection(18) ));

		//Maze
		std::vector<Point> E;		
		E.push_back(Point(2750-390, 0-400, 0));
		E.push_back(Point(2750-390, 800-400, 0));
		E.push_back(Point(780+300+600-390, 800-400, 0));
		E.push_back(Point(780+300+600-390, 800+980-400, 0));
		E.push_back(Point(780+300-390, 800+980-400, 0));
		E.push_back(Point(780+300-390, 800-400, 0));
		E.push_back(Point(780-390, 800-400, 0));
		E.push_back(Point(780-390, 1700-400, 0));
		E.push_back(Point(0-390, 1700-400, 0));
		E.push_back(Point(0-390, 0-400, 0));
		NEW_SHAPE(worldBounds, PolygonData, new PolygonData(worldShS, E, true));
		worldBounds->setColor("blue");

		// Virtual points
		NEW_SHAPE(snacks, PointData, new PointData(worldShS, Point(990-100,100,0)));
		snacks->setObstacle(false);
		NEW_SHAPE(cobot, PointData, new PointData(worldShS, Point(0,0,0)));
		cobot->setObstacle(false);
	}
	
	$nodeclass Loc : PilotNode(PilotTypes::localize) : doStart {
	    //particleFilter->resetFilter();
		if (pilotreq.landmarks.size() == 0) {
			cout << "Adding Landmarks" << endl;
			GET_SHAPE(tag0, AprilTagData, worldShS);
			GET_SHAPE(tag1, AprilTagData, worldShS);
			GET_SHAPE(tag2, AprilTagData, worldShS);
			GET_SHAPE(tag3, AprilTagData, worldShS);
			GET_SHAPE(tag4, AprilTagData, worldShS);
			GET_SHAPE(tag12, AprilTagData, worldShS);
			GET_SHAPE(tag17, AprilTagData, worldShS);
			GET_SHAPE(tag18, AprilTagData, worldShS);

			pilotreq.landmarks.push_back(tag0);
			pilotreq.landmarks.push_back(tag1);
			pilotreq.landmarks.push_back(tag2);
			pilotreq.landmarks.push_back(tag3);
			pilotreq.landmarks.push_back(tag4);
			pilotreq.landmarks.push_back(tag12);
			pilotreq.landmarks.push_back(tag17);
			pilotreq.landmarks.push_back(tag18);
		}

		MapBuilderRequest* req = new MapBuilderRequest(MapBuilderRequest::localMap);
		req->setAprilTagFamily(16,5);

		pilotreq.landmarkExtractor = req;
	}
	
	
	
	
	
	
	
	
    $nodeclass Starter : PilotNode(PilotTypes::goToShape) : doStart {
        GET_SHAPE(snacks, PointData, worldShS);
		pilotreq.targetShape = snacks;
		cout << "=======> Starter: " << snacks->getCentroid().coordX() << "," << snacks->getCentroid().coordY() << endl;
		pilotreq.collisionAction = collisionIgnore;
    }
    
    $nodeclass Turner : PilotNode(PilotTypes::walk) : doStart {
        pilotreq.collisionAction = collisionIgnore;
        pilotreq.da = atan2(FOODY-theAgent->getCentroid().coordY(), FOODX-theAgent->getCentroid().coordX()) - theAgent->getOrientation();
    }
    
    $nodeclass FindSnacks : MapBuilderNode(MapBuilderRequest::worldMap) : doStart {
        NEW_SHAPE(food, PointData, new PointData(worldShS, Point(FOODX, FOODY, 0, allocentric)));
        mapreq.searchArea = food;

        mapreq.addObjectColor(blobDataType, "red");
        mapreq.addBlobOrientation("red",BlobData::pillar);
        mapreq.addObjectColor(blobDataType, "blue");
        mapreq.addBlobOrientation("blue",BlobData::pillar);
    }
    
    $nodeclass ArmMover : PostureNode : doStart {
        for(unsigned int off = ArmOffset; off < ArmOffset+NumArmJoints; off++) {
            getMC()->setMaxSpeed(off, 0.3);
        }
        NEW_SHAPEVEC(cans, BlobData, select_type<BlobData>(localShS));
		fmat::Column<3> noOffset = fmat::pack(0, 0, 0);
		fmat::Column<3> target = fmat::pack(0,0,0);
		target[0] = cans[0]->getCentroid().coordX();
		target[1] = cans[0]->getCentroid().coordY();
		target[2] = 100;
		cout << "========> Reaching for " << target[0] << "," << target[1] << "," << target[2] << endl;
        getMC()->solveLinkPosition(target, HAND, noOffset);
    }
    
    $setupmachine {
        startdemo: DynamicMotionSequenceNode("arm_ready.mot") =C=> Loc =PILOT=> Starter =PILOT=> Turner =PILOT=> FindSnacks =C=> ArmMover =C=> SpeechNode("done.") =C=> PostMachineCompletion()
    }
}


REGISTER_BEHAVIOR(GetSnack);
