Vector3 computeDesiredForce(const SE3Type & pose, const Vector3 & linear_velocity,
			double delta_time) {
		    Vector3 desired_position(0,0,1);
            Vector3 desired_velocity(0,0,0);

//            Vector3 kp(1,1,1) ;
//            Vector3 kd(1,1,1);
//            Vector3 ki(0.0015,0.0015,0.0015) ;

//for ukf after redirecting to log
            Vector3 kp(4,4,4) ;
            Vector3 kd(3,3,3);
            Vector3 ki(0.002,0.002,0.002) ;


            Vector3 current_position=pose.translation();
            std::cout << "\nCurrent Position" << current_position ;
            Vector3 proportiona_val= kp.cwiseProduct(desired_position-current_position);
            Vector3 differential_val=kd.cwiseProduct(desired_velocity-linear_velocity);

            accumulated_error = accumulated_error+(desired_position-current_position) ;

            Vector3 integral_value=ki.cwiseProduct(accumulated_error);
            Vector3 desired_force=proportiona_val+ differential_val+integral_value;

            std::cout << "\ndesired_force is" << desired_force ;

            return desired_force;



	}
	void groundTruthPoseCallback(
			const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg) {
		Eigen::Quaterniond orientation;
		Eigen::Vector3d position;

		tf::pointMsgToEigen(msg->pose.pose.position, position);
		tf::quaternionMsgToEigen(msg->pose.pose.orientation, orientation);

		SE3Type pose(orientation.cast<_Scalar>(), position.cast<_Scalar>());

		ground_truth_linear_velocity = (pose.translation()
				- ground_truth_pose.translation())
				/ (msg->header.stamp.toSec() - ground_truth_time);

		ground_truth_pose = pose;
		ground_truth_time = msg->header.stamp.toSec();



	}