diff --git a/ros/src/.config/quick_start/sample_lidar_camera/mission_planning.launch b/ros/src/.config/quick_start/sample_lidar_camera/mission_planning.launch index d3a5b20be9d..3d22061e9e7 100755 --- a/ros/src/.config/quick_start/sample_lidar_camera/mission_planning.launch +++ b/ros/src/.config/quick_start/sample_lidar_camera/mission_planning.launch @@ -18,9 +18,9 @@ - + - + diff --git a/ros/src/computing/perception/localization/packages/ndt_localizer/nodes/ndt_matching/ndt_matching.cpp b/ros/src/computing/perception/localization/packages/ndt_localizer/nodes/ndt_matching/ndt_matching.cpp index e4d23d68efb..7afd8a62ae1 100644 --- a/ros/src/computing/perception/localization/packages/ndt_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/ros/src/computing/perception/localization/packages/ndt_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -139,8 +139,8 @@ static std_msgs::Bool ndt_stat_msg; static ros::Time current_scan_time; static ros::Time previous_scan_time; static ros::Duration scan_duration; -static ros::Publisher estimated_vel_pub; -static std_msgs::Float32 estimated_vel; +static ros::Publisher estimated_vel_mps_pub, estimated_vel_kmph_pub; +static std_msgs::Float32 estimated_vel_mps, estimated_vel_kmph; static std::chrono::time_point matching_start, matching_end;; static ros::Publisher time_ndt_matching_pub; @@ -855,9 +855,11 @@ static void velodyne_callback(const pcl::PointCloud("/ndt_stat", 1000); - estimated_vel_pub = nh.advertise("/estimated_vel", 1000); + estimated_vel_mps_pub = nh.advertise("/estimated_vel_mps", 1000); + + estimated_vel_kmph_pub = nh.advertise("/estimated_vel_kmph", 1000); time_ndt_matching_pub = nh.advertise("/time_ndt_matching", 1000); diff --git a/ros/src/computing/planning/motion/packages/waypoint_follower/CMakeLists.txt b/ros/src/computing/planning/motion/packages/waypoint_follower/CMakeLists.txt index edf661c64b2..79d162c037e 100644 --- a/ros/src/computing/planning/motion/packages/waypoint_follower/CMakeLists.txt +++ b/ros/src/computing/planning/motion/packages/waypoint_follower/CMakeLists.txt @@ -101,7 +101,7 @@ add_executable(twist_through nodes/collision_avoid/twist_through.cpp) target_link_libraries(twist_through ${catkin_LIBRARIES}) add_executable(velocity_set nodes/velocity_set/velocity_set.cpp) -target_link_libraries(velocity_set ${catkin_LIBRARIES}) -add_dependencies(velocity_set - waypoint_follower_generate_messages_cpp) +target_link_libraries(velocity_set libwaypoint_follower ${catkin_LIBRARIES}) +add_dependencies(velocity_set +waypoint_follower_generate_messages_cpp) diff --git a/ros/src/computing/planning/motion/packages/waypoint_follower/launch/velocity_set.launch b/ros/src/computing/planning/motion/packages/waypoint_follower/launch/velocity_set.launch new file mode 100644 index 00000000000..d1aa1d4a382 --- /dev/null +++ b/ros/src/computing/planning/motion/packages/waypoint_follower/launch/velocity_set.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/ros/src/computing/planning/motion/packages/waypoint_follower/nodes/velocity_set/velocity_set.cpp b/ros/src/computing/planning/motion/packages/waypoint_follower/nodes/velocity_set/velocity_set.cpp index d4e7b5df316..604464dd989 100644 --- a/ros/src/computing/planning/motion/packages/waypoint_follower/nodes/velocity_set/velocity_set.cpp +++ b/ros/src/computing/planning/motion/packages/waypoint_follower/nodes/velocity_set/velocity_set.cpp @@ -29,27 +29,654 @@ */ #include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + #include -static ros::Publisher _pub; +#include "waypoint_follower/lane.h" +#include "waypoint_follower/libwaypoint_follower.h" + +#define LOOP_RATE 10 + +static geometry_msgs::TwistStamped _current_twist; +static geometry_msgs::PoseStamped _current_pose; // current pose by the global plane. +static pcl::PointCloud _vscan; + +static std::string _current_pose_topic = "ndt"; +static const std::string pedestrian_sound = "pedestrian"; +static std::string _linelist_frame = "/velodyne"; +//static bool _twist_flag = false; +static bool _pose_flag = false; +static bool _path_flag = false; +static bool _vscan_flag = false; +static bool _changepath_flag = false; + +static double _detection_range = 0; +static int _obstacle_waypoint = -1; +static int _threshold_points = 15; +static double _detection_height_top = 2.0; //actually +2.0m +static double _detection_height_bottom = -2.0; +static double _search_distance = 70; +static int _stop_interval = 5; +static double _car_distance = 8.0; // meter :distance from a front car when stopped +static int _closest_waypoint = -1; +static double _current_vel = 0; // subscribe estimated_vel_mps +static double _decel = 1.5; // (m/s) deceleration +static double _decel_limit = 2.778; // (m/s) about 10 km/h +static visualization_msgs::Marker _linelist; // for obstacle's vscan linelist +static tf::Transform _transform; + +//Publisher +//static ros::Publisher _twist_pub; +static ros::Publisher _vis_pub; +static ros::Publisher _range_pub; +static ros::Publisher _sound_pub; +static ros::Publisher _safety_waypoint_pub; +static ros::Publisher _linelist_pub; + +Path _path_dk; + +class PathVset: public Path{ +private: +public: + void changeWaypoints(int stop_waypoint); + double getVel(int num); + void avoidSuddenBraking(); +}; +PathVset _path_change; + + + +//=============================== +// class function +//=============================== + + +double PathVset::getVel(int num){ + + if (current_path_.waypoints.empty() || num < 0){ + std::cout << "getVel: invalid waypoint" << std::endl; + return 0.0; + } + + return current_path_.waypoints[num].twist.twist.linear.x; +} + + + +void PathVset::avoidSuddenBraking(){ + int i = 0; + int path_size = getPathSize(); + int close_waypoint_threshold = 5; + int fill_in_zero = 5; + int fill_in_vel = 15; + int num; + double temp; + double interval = getInterval(); + + std::cout << "====avoid sudden braking====" << std::endl; + std::cout << "vehicle is decelerating..." << std::endl; + _closest_waypoint = getClosestWaypoint(); + std::cout << "closest_waypoint: " << _closest_waypoint << std::endl; + for (num = _closest_waypoint - close_waypoint_threshold; fill_in_vel > 0; fill_in_vel--){ + if (num-fill_in_vel < 0 || num >= path_size){ + std::cout << "avoidSuddenBraking: invalid waypoint number" << std::endl; + continue; + } + current_path_.waypoints[num-fill_in_vel].twist.twist.linear.x = _current_vel; + } + + for (num = _closest_waypoint - close_waypoint_threshold; num > -1; num++){ + if (num < 0 || num >= path_size){ + std::cout << "avoidSuddenBraking: invalid waypoint number" << std::endl; + return; + } + temp = _current_vel*_current_vel - 2*_decel*i*interval; // sqrt(v^2 - 2*a*x) + if (temp > 0){ + //if (sqrt(temp) > getVel(num)){current_path_.waypoints[num].twist.twist.linear.x = getVel(num);} + current_path_.waypoints[num].twist.twist.linear.x = sqrt(temp);// + //std::cout << "waypoint[" << num << "] vel: " << mps2kmph(sqrt(temp)) << std::endl; + } else { + break; + } + i++; + } + + if (num < 0){ + std::cout << "avoidSuddenBraking: invalid waypoint number" << std::endl; + return; + } + for (int j = 0; j < fill_in_zero; j++){current_path_.waypoints[num+j].twist.twist.linear.x = 0.0;} + + _safety_waypoint_pub.publish(current_path_);// publish new waypoints + std::cout << "====published waypoints====" << std::endl; + + return; +} + + +void PathVset::changeWaypoints(int stop_waypoint){ + int i = 0; + int path_size = getPathSize(); + int close_waypoint_threshold = 4; + int fill_in_zero = 10; + double changed_vel; + double interval = getInterval(); + + + _closest_waypoint = getClosestWaypoint(); + if (_closest_waypoint < 0){ + std::cout << "changeWaypoints: invalid waypoint number" << std::endl; + return; + } + + for (int num = _closest_waypoint + close_waypoint_threshold; num > _closest_waypoint-5; num--){ + if (getVel(num) < _current_vel - _decel_limit){ + avoidSuddenBraking(); + return; + } + } + + for (int num = stop_waypoint; num > _closest_waypoint - close_waypoint_threshold; num--){ + if (num < 0 || num >= path_size){ + std::cout << "invalid waypoint number" << std::endl; + return; + } + changed_vel = sqrt(2.0*_decel*(interval*i)); // sqrt(2*a*x) + + std::cout << "changed_vel[" << num << "]: " << mps2kmph(changed_vel) << " (km/h)"; + std::cout << " distance: " << (_obstacle_waypoint-num)*interval << " (m)"; + std::cout << " current_vel: " << mps2kmph(_current_vel) << std::endl; + + // avoid sudden braking at close waypoint + if (num < _closest_waypoint + close_waypoint_threshold){ + if (changed_vel < _current_vel - _decel_limit){ + avoidSuddenBraking(); + return; + } + } + + if (changed_vel > _current_vel || + changed_vel > _path_dk.getCurrentPath().waypoints[num].twist.twist.linear.x){ // avoid acceleration + std::cout << "too large velocity!!" << std::endl; + current_path_.waypoints[num].twist.twist.linear.x = current_path_.waypoints[num+1].twist.twist.linear.x; + } else { + current_path_.waypoints[num].twist.twist.linear.x = changed_vel; // set waypoint velocity to decelerate + } + + i++; + } + // fill in 0 + for (int j = 1; j < fill_in_zero; j++){ + if (stop_waypoint+j < _closest_waypoint+close_waypoint_threshold && + _current_vel > _decel_limit){ + avoidSuddenBraking(); + return; + } + current_path_.waypoints[stop_waypoint+j].twist.twist.linear.x = 0; + } + + _safety_waypoint_pub.publish(current_path_);// publish new waypoints + std::cout << "---published waypoints---" << std::endl; + + return; +} + + +//=============================== +// class function +//=============================== + + + + + +//=============================== +// Callback +//=============================== + +void EstimatedVelCallback(const std_msgs::Float32ConstPtr &msg){ + + _current_vel = msg->data; +} + +void BaseWaypointCallback(const waypoint_follower::laneConstPtr &msg){ + + ROS_INFO("subscribed safety_waypoint\n"); + _path_dk.setPath(msg); + _path_change.setPath(msg); //++ + if (_path_flag == false) { + std::cout << "waypoint subscribed" << std::endl; + _path_flag = true; + } + + _safety_waypoint_pub.publish(msg); + +} + + +void ObjPoseCallback(const visualization_msgs::MarkerConstPtr &msg){ + + ROS_INFO("subscribed obj_pose\n"); + +} + + +/* +static void TwistCmdCallback(const geometry_msgs::TwistStampedConstPtr &msg) +{ + _current_twist = *msg; + + if (_twist_flag == false) { + std::cout << "twist subscribed" << std::endl; + _twist_flag = true; + } +} +*/ + +static void VscanCallback(const sensor_msgs::PointCloud2ConstPtr &msg) +{ + pcl::fromROSMsg(*msg, _vscan); + if (_vscan_flag == false) { + std::cout << "vscan subscribed" << std::endl; + _vscan_flag = true; + } + +} + +static void NDTCallback(const geometry_msgs::PoseStampedConstPtr &msg) +{ + _current_pose.header = msg->header; + _current_pose.pose = msg->pose; + tf::Transform inverse; + tf::poseMsgToTF(msg->pose, inverse); + _path_dk.setTransform(inverse.inverse()); + _path_change.setTransform(inverse.inverse());//++ + if (_pose_flag == false) { + std::cout << "pose subscribed" << std::endl; + _pose_flag = true; + } +} + +//=============================== +// Callback +//=============================== + + + + -void callback(const waypoint_follower::lane &msg) +// display by markers. +static void DisplayObstacleWaypoint(int i) { - _pub.publish(msg); + + visualization_msgs::Marker marker; + marker.header.frame_id = "/map"; + marker.header.stamp = ros::Time(); + marker.ns = "my_namespace"; + marker.id = 0; + marker.type = visualization_msgs::Marker::CUBE; + marker.action = visualization_msgs::Marker::ADD; + marker.pose.position = _path_dk.getWaypointPosition(i); + marker.pose.orientation = _current_pose.pose.orientation; + marker.scale.x = 1.0; + marker.scale.y = 1.0; + marker.scale.z = _detection_height_top; + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 0.0; + marker.color.b = 1.0; + marker.lifetime = ros::Duration(0.1); + marker.frame_locked = true; + + _vis_pub.publish(marker); +} + +// display by markers. +static void DisplayDetectionRange(int i) +{ + + visualization_msgs::Marker marker; + marker.header.frame_id = "/map"; + marker.header.stamp = ros::Time(); + marker.ns = "my_namespace"; + marker.id = 0; + marker.type = visualization_msgs::Marker::SPHERE_LIST; + marker.action = visualization_msgs::Marker::ADD; + + for (int j = 0; j < _search_distance; j++) { + if(i+j > _path_dk.getPathSize() - 1) + break; + + geometry_msgs::Point point; + point = _path_dk.getWaypointPosition(j+i); + marker.points.push_back(point); + } + marker.scale.x = 2 * _detection_range; + marker.scale.y = 2 * _detection_range; + marker.scale.z = _detection_height_top; + marker.color.a = 0.2; + marker.color.r = 0.0; + marker.color.g = 1.0; + marker.color.b = 0.0; + marker.frame_locked = true; + + _range_pub.publish(marker); + marker.points.clear(); +} + +static int vscanDetection(int closest_waypoint) +{ + + if (_vscan.empty() == true) + return -1; + + for (int i = closest_waypoint + 1; i < closest_waypoint + _search_distance; i++) { + + if(i > _path_dk.getPathSize() - 1 ) + return -1; + + tf::Vector3 tf_waypoint = _path_dk.transformWaypoint(i); // waypoint seen by vehicle + tf_waypoint.setZ(0); + //std::cout << "waypoint : "<< tf_waypoint.getX() << " "<< tf_waypoint.getY() << std::endl; + + int point_count = 0; + geometry_msgs::Point vscan_point; + _linelist.points.clear(); + for (pcl::PointCloud::const_iterator item = _vscan.begin(); item != _vscan.end(); item++) { + // out of detection range + if ((item->x == 0 && item->y == 0) /*|| item->z > _detection_height_top || + item->z < _detection_height_bottom*/){ + continue; + } + + tf::Vector3 point((double) item->x, (double) item->y, 0); + + // 2D distance between waypoint and vscan point(obstacle) + double dt = tf::tfDistance(point, tf_waypoint); + if (dt < _detection_range) { + vscan_point.x = item->x; + vscan_point.y = item->y; + vscan_point.z = item->z; + _linelist.points.push_back(vscan_point); + if (item->z > _detection_height_top || item->z < _detection_height_bottom){continue;} + point_count++; + } + + // return closest waypoint from obstacles + if (point_count > _threshold_points){ + //_linelist_pub.publish(_linelist); + _linelist.points.clear(); + return i; + } + } + } + + // no obstacles + return -1; +} + +static void SoundPlay(){ + std_msgs::String string; + string.data = pedestrian_sound; + _sound_pub.publish(string); +} + +static bool ObstacleDetection() +{ + static int false_count = 0; + static bool prev_detection = false; + + int closest_waypoint = _path_change.getClosestWaypoint(); // + _closest_waypoint = closest_waypoint;// + std::cout << "closest_waypoint : " << closest_waypoint << std::endl; + DisplayDetectionRange(closest_waypoint + 1); + int vscan_result = vscanDetection(closest_waypoint); + + if (prev_detection == false) { + if (vscan_result != -1) { // found obstacle + DisplayObstacleWaypoint(vscan_result); + std::cout << "obstacle waypoint : " << vscan_result << std::endl << std::endl; + prev_detection = true; + _obstacle_waypoint = vscan_result; + SoundPlay(); + false_count = 0; + return true; + } else { // no obstacle + prev_detection = false; + return false; + } + } else { //prev_detection = true + if (vscan_result != -1) { // found obstacle + DisplayObstacleWaypoint(vscan_result); + std::cout << "obstacle waypoint : " << vscan_result << std::endl << std::endl; + prev_detection = true; + _obstacle_waypoint = vscan_result; + false_count = 0; + + return true; + } else { // no obstacle + false_count++; + std::cout << "false_count : "<< false_count << std::endl; + } + + //fail-safe + if (false_count >= LOOP_RATE * 2) { + _obstacle_waypoint = -1; + false_count = 0; + prev_detection = false; + return false; + } else { + std::cout << "obstacle waypoint : " << _obstacle_waypoint << std::endl << std::endl; + DisplayObstacleWaypoint(_obstacle_waypoint); + prev_detection = true; + + return true; + } + } + + + +} + +/* +static double Decelerate() +{ + //calculate distance from my position to waypoint + //tf::Vector3 tf_waypoint = TransformWaypoint(_transform,_current_path.waypoints[_obstacle_waypoint].pose.pose); + tf::Vector3 tf_waypoint = _path_dk.transformWaypoint(_obstacle_waypoint); + tf::Vector3 origin_v; + origin_v.setZero(); + double distance = tf::tfDistance(origin_v, tf_waypoint); + // std::cout << "distance " << distance << std::endl; + + //if distance is within stop_interval param, publish 0km/h + if(distance < _stop_interval){ + return 0; + } + + double decel_velocity_ms = DecelerateVelocity(distance,_current_twist.twist.linear.x); + + if(decel_velocity_ms < 1.0){ + decel_velocity_ms = 0; + } + + return decel_velocity_ms; + +} +*/ + +// publish obstacles as RED linelist +static void linelistInit() +{ + + _linelist.header.frame_id = _linelist_frame; + _linelist.header.stamp = ros::Time(0); + _linelist.ns = "vscan_linelist"; + _linelist.id = 0; + _linelist.type = visualization_msgs::Marker::LINE_LIST; + _linelist.action = visualization_msgs::Marker::ADD; + _linelist.scale.x = 0.15; + _linelist.color.a = 0.5; + _linelist.color.r = 1.0; + _linelist.color.g = 0.0; + _linelist.color.b = 0.0; + +} + + +static void ChangeWaypoint(bool detection_result) +{ + + int obs = _obstacle_waypoint; + waypoint_follower::lane lane; + + if (obs != -1){ + std::cout << "====got obstacle waypoint====" << std::endl; + lane = _path_change.getCurrentPath(); + std::cout << "waypoint[" << obs << "] velocity: " << lane.waypoints[obs].twist.twist.linear.x << std::endl; + std::cout << "getDistance: " << _path_change.getDistance(obs) << std::endl; + std::cout << "=============================" << std::endl; + } + + _closest_waypoint = _path_change.getClosestWaypoint(); + if (detection_result){ // DECELERATE + // if obstacle is behind a vehicle, return + if (obs < _closest_waypoint){ + std::cout << "ChangeWaypoint: invalid obstacle waypoint" << std::endl; + return; + } + // *stop_waypoint is about _car_distance meter away from obstacle* + int stop_waypoint = obs - (((int)_car_distance / _path_change.getInterval())); + std::cout << "stop_waypoint: " << stop_waypoint << std::endl; + if (stop_waypoint < 0){ + std::cout << "ChangeWaypoint: invalid stop_waypoint!" << std::endl; + return; + } + _path_change.changeWaypoints(stop_waypoint); + _changepath_flag = true; + } else { // ACELERATE or KEEP + if (_changepath_flag){ + _safety_waypoint_pub.publish(_path_dk.getCurrentPath());/// + _changepath_flag = false; + } + } + + + + + return; } + + +//====================================== +// main +//====================================== + int main(int argc, char **argv) { + int i = 0;/// ros::init(argc, argv, "velocity_set"); ros::NodeHandle nh; - ros::Subscriber twist_sub = nh.subscribe("base_waypoint", 1, callback); - _pub = nh.advertise("safety_waypoint", 1000,true); + ros::NodeHandle private_nh("~"); + //ros::Subscriber twist_sub = nh.subscribe("twist_raw", 1, TwistCmdCallback); + ros::Subscriber ndt_sub = nh.subscribe("control_pose", 1, NDTCallback); + ros::Subscriber vscan_sub = nh.subscribe("vscan_points", 1, VscanCallback); + ros::Subscriber base_waypoint_sub = nh.subscribe("base_waypoint", 1, BaseWaypointCallback); + ros::Subscriber obj_pose_sub = nh.subscribe("obj_pose", 1, ObjPoseCallback); + ros::Subscriber estimated_vel_sub = nh.subscribe("estimated_vel_mps", 1, EstimatedVelCallback); + + //_twist_pub = nh.advertise("twist_cmd", 1000); + _vis_pub = nh.advertise("obstaclewaypoint_mark", 0); + _range_pub = nh.advertise("detection_range", 0); + _sound_pub = nh.advertise("sound_player", 10); + _safety_waypoint_pub = nh.advertise("safety_waypoint", 1000); + _linelist_pub = nh.advertise("vscan_linelist", 10); + + + + private_nh.getParam("detection_range", _detection_range); + std::cout << "detection_range : " << _detection_range << std::endl; + + private_nh.getParam("threshold_points", _threshold_points); + std::cout << "threshold_points : " << _threshold_points << std::endl; + + private_nh.getParam("stop_interval", _stop_interval); + std::cout << "stop_interval : " << _stop_interval << std::endl; + + private_nh.getParam("detection_height_top", _detection_height_top); + std::cout << "detection_height_top : " << _detection_height_top << std::endl; + + private_nh.getParam("detection_height_bottom", _detection_height_bottom); + std::cout << "detection_height_bottom : " << _detection_height_bottom << std::endl; + + private_nh.getParam("current_pose_topic", _current_pose_topic); + std::cout << "current_pose_topic : " << _current_pose_topic << std::endl; + + linelistInit(); + + ros::Rate loop_rate(LOOP_RATE); + while (ros::ok()) { + ros::spinOnce(); + + if (_pose_flag == false || _path_flag == false) { + std::cout << "\rtopic waiting \rtopic waiting"; + for (int j = 0; j < i; j++) {std::cout << ".";} + i++; + i = i%10; + std::cout << std::flush; + loop_rate.sleep(); + continue; + } + + bool detection_result = ObstacleDetection(); + + + /* change waypoints to avoid collision */ + /* if detection_result is true,and then it becomes false,we have to Accelerate */ + ChangeWaypoint(detection_result); + + + /* + if (_twist_flag == true) { + geometry_msgs::TwistStamped twist; + if (detection_result == true) { + //decelerate + std::cout << "twist deceleration..." << std::endl; + twist.twist.linear.x = Decelerate(); + twist.twist.angular.z = _current_twist.twist.angular.z; + } else { + //through + std::cout << "twist through" << std::endl; + twist.twist = _current_twist.twist; + } + std::cout << "twist.linear.x = " << twist.twist.linear.x << std::endl; + std::cout << "twist.angular.z = " << twist.twist.angular.z << std::endl; + std::cout << std::endl; - ros::spin(); + twist.header.stamp = _current_twist.header.stamp; + _twist_pub.publish(twist); + } else { + std::cout << "no twist topic" << std::endl; + } + */ + loop_rate.sleep(); + } return 0; diff --git a/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp b/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp index 97227307f01..4f7fee988a9 100644 --- a/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp +++ b/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp @@ -72,7 +72,7 @@ int main(int argc, char **argv) n.param("/waypoint_clicker/velocity", velocity, 40); n.param("/waypoint_clicker/output_file", output_file, "/tmp/lane_waypoint.csv"); - ros::Subscriber sub_point = n.subscribe("/clicked_point", sub_point_queue_size, write_clicked_point); + ros::Subscriber sub_point = n.subscribe("/initialpose", sub_point_queue_size, write_clicked_point); tf::TransformListener listener; try { diff --git a/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp b/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp index 94237405c97..1197e850c73 100644 --- a/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp +++ b/ros/src/computing/planning/motion/packages/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp @@ -186,6 +186,17 @@ static void trafficCallback(const waypoint_follower::laneConstPtr &msg) } +static void safetyCallback(const waypoint_follower::laneConstPtr &msg) +{ + visualization_msgs::MarkerArray marker_array; + createWaypointVelocityMarker(*msg, &marker_array); + createWaypointMarker(*msg, &marker_array); + createPathMarker(_color, *msg, &marker_array); + + _lane_mark_pub.publish(marker_array); + +} + int main(int argc, char **argv) { ros::init(argc, argv, "marker_publisher"); @@ -195,6 +206,7 @@ int main(int argc, char **argv) ros::Subscriber lane_sub = nh.subscribe("lane_waypoint",10,laneCallback); ros::Subscriber traffic_sub = nh.subscribe("traffic_waypoint",10,trafficCallback); ros::Subscriber light_sub = nh.subscribe("traffic_light",10,lightCallback); + ros::Subscriber safety_sub = nh.subscribe("safety_waypoint",10,safetyCallback); _lane_mark_pub = nh.advertise("lane_waypoint_mark", 10, true); diff --git a/ros/src/socket/packages/oculus_socket/launch/oculus_sender.launch b/ros/src/socket/packages/oculus_socket/launch/oculus_sender.launch index e24a62c30f8..478aae6bcfb 100644 --- a/ros/src/socket/packages/oculus_socket/launch/oculus_sender.launch +++ b/ros/src/socket/packages/oculus_socket/launch/oculus_sender.launch @@ -1,3 +1,3 @@ - + diff --git a/ros/src/socket/packages/oculus_socket/nodes/oculus_sender/oculus_sender.cpp b/ros/src/socket/packages/oculus_socket/nodes/oculus_sender/oculus_sender.cpp index 2e84c2df375..58e14edda8a 100644 --- a/ros/src/socket/packages/oculus_socket/nodes/oculus_sender/oculus_sender.cpp +++ b/ros/src/socket/packages/oculus_socket/nodes/oculus_sender/oculus_sender.cpp @@ -36,7 +36,7 @@ geometry_msgs::Point prev; struct timeval t; -static void ndt_pose_Callback(const geometry_msgs::PoseStamped::ConstPtr& input) +static void current_pose_Callback(const geometry_msgs::PoseStamped::ConstPtr& input) { tf::Quaternion q(input->pose.orientation.x, input->pose.orientation.y, input->pose.orientation.z, input->pose.orientation.w); @@ -52,9 +52,8 @@ static void ndt_pose_Callback(const geometry_msgs::PoseStamped::ConstPtr& input) sendto(sock1, buf1, sizeof(buf1), 0, (struct sockaddr *)&addr1, sizeof(addr1)); } -static void car_pose_Callback(const visualization_msgs::MarkerArray::ConstPtr& input) +static void obj_pose_Callback(const visualization_msgs::MarkerArray::ConstPtr& input) { - for (std::vector::const_iterator item = input->markers.begin(); item != input->markers.end(); item++){ tf::Quaternion q(item->pose.orientation.x, item->pose.orientation.y, item->pose.orientation.z, item->pose.orientation.w); @@ -64,8 +63,16 @@ static void car_pose_Callback(const visualization_msgs::MarkerArray::ConstPtr& i ROS_INFO("x=[%.6f] y=[%.6f] z=[%.6f]", item->pose.position.x, item->pose.position.y, item->pose.position.z); ROS_INFO("roll=[%f] pitch=[%f] yaw=[%f], PI=[%f]", roll/PI*180, pitch/PI*180, yaw/PI*180, PI); - gettimeofday(&t,NULL); - sprintf(buf1,"%ld%ld OTH %d %f %f %f %f %f %f", t.tv_sec, t.tv_usec , 0, item->pose.position.x, item->pose.position.y, item->pose.position.z, roll/PI*180, pitch/PI*180, yaw/PI*180); + gettimeofday(&t,NULL); + if(item->color.b == 1.0f){ + sprintf(buf1,"%ld%ld OTH %d %f %f %f %f %f %f", t.tv_sec, t.tv_usec , 0, item->pose.position.x, item->pose.position.y, item->pose.position.z, roll/PI*180, pitch/PI*180, yaw/PI*180); + } + else if(item->color.g == 1.0f){ + sprintf(buf1,"%ld%ld PED %d %f %f %f %f %f %f", t.tv_sec, t.tv_usec , 0, item->pose.position.x, item->pose.position.y, item->pose.position.z, roll/PI*180, pitch/PI*180, yaw/PI*180); + } + else { + sprintf(buf1,"%ld%ld OBJ %d %f %f %f %f %f %f", t.tv_sec, t.tv_usec , 0, item->pose.position.x, item->pose.position.y, item->pose.position.z, roll/PI*180, pitch/PI*180, yaw/PI*180); + } sendto(sock1, buf1, sizeof(buf1), 0, (struct sockaddr *)&addr1, sizeof(addr1)); } @@ -99,9 +106,10 @@ int main (int argc, char **argv) ros::init(argc,argv,"udp_sender"); ros::NodeHandle n; - ros::Subscriber ndt_pose_sub = n.subscribe("ndt_pose",1000,ndt_pose_Callback); + ros::Subscriber current_pose_sub = n.subscribe("current_pose",1000,current_pose_Callback); // ros::Subscriber vscan_sub = n.subscribe("vscan_points", 100, vscan_Callback); - ros::Subscriber car_pose_sub = n.subscribe("car_pose",1000,car_pose_Callback); + ros::Subscriber obj_car_sub = n.subscribe("obj_car/obj_pose",1000,obj_pose_Callback); + ros::Subscriber obj_person_sub = n.subscribe("obj_person/obj_pose",1000,obj_pose_Callback); sock1 = socket(AF_INET, SOCK_DGRAM, 0); diff --git a/ros/src/util/packages/runtime_manager/scripts/computing.yaml b/ros/src/util/packages/runtime_manager/scripts/computing.yaml index 9cedf51e803..60c97819ea5 100644 --- a/ros/src/util/packages/runtime_manager/scripts/computing.yaml +++ b/ros/src/util/packages/runtime_manager/scripts/computing.yaml @@ -185,10 +185,10 @@ subs : cmd : rosrun lane_planner lane_select gui : dialog: MyDialogLaneStop - - name : parking_planner + - name : freespace_planner subs : - - name : XXX - cmd : echo "XXX" + - name : astar_navi + cmd : rosrun freespace_planner astar_navi - name : Motion Planning subs : @@ -235,7 +235,7 @@ subs : depend : param_flag stat_topic : [ lf ] - name : velocity_set - cmd : rosrun waypoint_follower velocity_set + cmd : roslaunch waypoint_follower velocity_set.launch - name : collision_avoid cmd : roslaunch waypoint_follower collision_avoid.launch - name : twist_through diff --git a/ui/oculus/ofw/Makefile b/ui/oculus/ofw/Makefile new file mode 100644 index 00000000000..7a7fe8b58f6 --- /dev/null +++ b/ui/oculus/ofw/Makefile @@ -0,0 +1,13 @@ +# Attempt to load a config.make file. +# If none is found, project defaults in config.project.make will be used. +ifneq ($(wildcard config.make),) + include config.make +endif + +# make sure the the OF_ROOT location is defined +ifndef OF_ROOT + OF_ROOT=../../.. +endif + +# call the project makefile! +include $(OF_ROOT)/libs/openFrameworksCompiled/project/makefileCommon/compile.project.mk diff --git a/ui/oculus/ofw/README.txt b/ui/oculus/ofw/README.txt new file mode 100644 index 00000000000..32b1b370e51 --- /dev/null +++ b/ui/oculus/ofw/README.txt @@ -0,0 +1,42 @@ +*環境構築 + -Linux + ・Ubuntu 14.04 + + -Oculus + ・Oculus DK2 + ・SDK ovr_sdk_linux_0.4.4 + + -openFrameworks + ・バージョン of_v0.8.4_linux64_release + + ・手順 + 1.openFrameworks のサイト(http://openframeworks.jp/)より code::blocks(64 bit) をダウンロード + 2.IDE setup guide の手順に従いセットアップ + 3.openFrameworks の addons より ofxOculusDK2 (https://github.com/sphaero/ofxOculusDK2/tree/linux_0.4.4)をダウンロード + 4.of_v0.8.4_linux64_release の addons ディレクトリ以下に ofxOculusDK2 を置く + 5.of_v0.8.4_linux64_release の apps ディレクトリ以下の projectGenerator よりプロジェクトを作成する。(プロジェクト名称は任意) + 6.作成したプロジェクトの bin/data ディレクトリ, src ディレクトリ, Makefile, addons.make, config.make を このディレクトリ(Autoware/ui/oculus/ofw/) のものに置き換える。 + +*使用方法 + + ・ROS側 + 1.oculus_sender の起動(runtime_maneger の Oculus_Rift ボタン) + + ↓ runtime_maneger を使用しない場合 (現時点ではこちらのみ?) ↓ + 2.端末上で以下のコマンド入力 Oculus PC の ipアドレス を引数にとる + $ roslaunch oculus oculus_sender.launch ip:= "xxx.xxx.xxx.xxx" + + ・ofw側 + 1.ソースコード内、各mapのディレクトリパスの変更 +  -pointcloud_map.hの変更 +    #define PCD_DIR を 読み込みたいディレクトリのパスに設定 +    #define STATIC_DIR を 読み込みたいディレクトリのパスに設定 +  -testApp.hの変更 +    #define VECTOR を 読み込みたいディレクトリのパスに設定 + 2.プロジェクトの起動 + + ・Oculus SDK 0.4.4 + 1.ofw の実行の前に Oculus SDK 内で +     % ./oculusd +  を実行する必要がある。 + diff --git a/ui/oculus/ofw/addons.make b/ui/oculus/ofw/addons.make new file mode 100644 index 00000000000..0b0ac3338b6 --- /dev/null +++ b/ui/oculus/ofw/addons.make @@ -0,0 +1,3 @@ +ofxNetwork +ofxAssimpModelLoader +ofxOculusDK2 diff --git a/ui/oculus/ofw/config.make b/ui/oculus/ofw/config.make new file mode 100644 index 00000000000..f9aae4ee2bc --- /dev/null +++ b/ui/oculus/ofw/config.make @@ -0,0 +1,142 @@ +################################################################################ +# CONFIGURE PROJECT MAKEFILE (optional) +# This file is where we make project specific configurations. +################################################################################ + +################################################################################ +# OF ROOT +# The location of your root openFrameworks installation +# (default) OF_ROOT = ../../.. +################################################################################ +# OF_ROOT = ../../.. + +################################################################################ +# PROJECT ROOT +# The location of the project - a starting place for searching for files +# (default) PROJECT_ROOT = . (this directory) +# +################################################################################ +# PROJECT_ROOT = . + +################################################################################ +# PROJECT SPECIFIC CHECKS +# This is a project defined section to create internal makefile flags to +# conditionally enable or disable the addition of various features within +# this makefile. For instance, if you want to make changes based on whether +# GTK is installed, one might test that here and create a variable to check. +################################################################################ +# None + +################################################################################ +# PROJECT EXTERNAL SOURCE PATHS +# These are fully qualified paths that are not within the PROJECT_ROOT folder. +# Like source folders in the PROJECT_ROOT, these paths are subject to +# exlclusion via the PROJECT_EXLCUSIONS list. +# +# (default) PROJECT_EXTERNAL_SOURCE_PATHS = (blank) +# +# Note: Leave a leading space when adding list items with the += operator +################################################################################ +# PROJECT_EXTERNAL_SOURCE_PATHS = + +################################################################################ +# PROJECT EXCLUSIONS +# These makefiles assume that all folders in your current project directory +# and any listed in the PROJECT_EXTERNAL_SOURCH_PATHS are are valid locations +# to look for source code. The any folders or files that match any of the +# items in the PROJECT_EXCLUSIONS list below will be ignored. +# +# Each item in the PROJECT_EXCLUSIONS list will be treated as a complete +# string unless teh user adds a wildcard (%) operator to match subdirectories. +# GNU make only allows one wildcard for matching. The second wildcard (%) is +# treated literally. +# +# (default) PROJECT_EXCLUSIONS = (blank) +# +# Will automatically exclude the following: +# +# $(PROJECT_ROOT)/bin% +# $(PROJECT_ROOT)/obj% +# $(PROJECT_ROOT)/%.xcodeproj +# +# Note: Leave a leading space when adding list items with the += operator +################################################################################ +# PROJECT_EXCLUSIONS = + +################################################################################ +# PROJECT LINKER FLAGS +# These flags will be sent to the linker when compiling the executable. +# +# (default) PROJECT_LDFLAGS = -Wl,-rpath=./libs +# +# Note: Leave a leading space when adding list items with the += operator +# +# Currently, shared libraries that are needed are copied to the +# $(PROJECT_ROOT)/bin/libs directory. The following LDFLAGS tell the linker to +# add a runtime path to search for those shared libraries, since they aren't +# incorporated directly into the final executable application binary. +################################################################################ +# PROJECT_LDFLAGS=-Wl,-rpath=./libs +PROJECT_LDFLAGS=-lrt + +################################################################################ +# PROJECT DEFINES +# Create a space-delimited list of DEFINES. The list will be converted into +# CFLAGS with the "-D" flag later in the makefile. +# +# (default) PROJECT_DEFINES = (blank) +# +# Note: Leave a leading space when adding list items with the += operator +################################################################################ +# PROJECT_DEFINES = + +################################################################################ +# PROJECT CFLAGS +# This is a list of fully qualified CFLAGS required when compiling for this +# project. These CFLAGS will be used IN ADDITION TO the PLATFORM_CFLAGS +# defined in your platform specific core configuration files. These flags are +# presented to the compiler BEFORE the PROJECT_OPTIMIZATION_CFLAGS below. +# +# (default) PROJECT_CFLAGS = (blank) +# +# Note: Before adding PROJECT_CFLAGS, note that the PLATFORM_CFLAGS defined in +# your platform specific configuration file will be applied by default and +# further flags here may not be needed. +# +# Note: Leave a leading space when adding list items with the += operator +################################################################################ +# PROJECT_CFLAGS = + +################################################################################ +# PROJECT OPTIMIZATION CFLAGS +# These are lists of CFLAGS that are target-specific. While any flags could +# be conditionally added, they are usually limited to optimization flags. +# These flags are added BEFORE the PROJECT_CFLAGS. +# +# PROJECT_OPTIMIZATION_CFLAGS_RELEASE flags are only applied to RELEASE targets. +# +# (default) PROJECT_OPTIMIZATION_CFLAGS_RELEASE = (blank) +# +# PROJECT_OPTIMIZATION_CFLAGS_DEBUG flags are only applied to DEBUG targets. +# +# (default) PROJECT_OPTIMIZATION_CFLAGS_DEBUG = (blank) +# +# Note: Before adding PROJECT_OPTIMIZATION_CFLAGS, please note that the +# PLATFORM_OPTIMIZATION_CFLAGS defined in your platform specific configuration +# file will be applied by default and further optimization flags here may not +# be needed. +# +# Note: Leave a leading space when adding list items with the += operator +################################################################################ +# PROJECT_OPTIMIZATION_CFLAGS_RELEASE = +# PROJECT_OPTIMIZATION_CFLAGS_DEBUG = + +################################################################################ +# PROJECT COMPILERS +# Custom compilers can be set for CC and CXX +# (default) PROJECT_CXX = (blank) +# (default) PROJECT_CC = (blank) +# Note: Leave a leading space when adding list items with the += operator +################################################################################ +# PROJECT_CXX = +# PROJECT_CC = diff --git a/ui/oculus/ofw/data/prius_model.dae b/ui/oculus/ofw/data/prius_model.dae new file mode 100644 index 00000000000..116f33d7a4f --- /dev/null +++ b/ui/oculus/ofw/data/prius_model.dae @@ -0,0 +1,509 @@ + + + + + Assimp + Assimp Exporter + + 2015-04-15T15:40:54 + 2015-04-15T15:40:54 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.894118 0.894118 0.894118 1 + + + 1 1 1 1 + + + 26.5225 + + + 0 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.87451 0.87451 0.87451 1 + + + 1 1 1 1 + + + 36 + + + 0 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.87451 0.858824 0.443137 1 + + + 1 1 1 1 + + + 36 + + + 0.51 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.52549 0.0470588 0.027451 1 + + + 1 1 1 1 + + + 36 + + + 0 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.219608 0.219608 0.219608 1 + + + 1 1 1 1 + + + 16.4025 + + + 0 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.309804 0.309804 0.309804 1 + + + 1 1 1 1 + + + 0 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.247059 0.313726 0.435294 1 + + + 1 1 1 1 + + + 64 + + + 0.5 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1.73173 1.02078 0.7455 1.26952 0.988828 0.80514 1.26633 1.07403 0.73485 1.88722 1.11876 0.64326 0.0767244 1.47406 -0 -0.346882 1.36914 0.27 -0.359926 1.37436 -0 0.758324 1.45743 0.51546 0.0767244 1.46264 0.485052 0.758324 1.45956 -0 -1.89779 0.238642 0.77319 -1.79981 0.204988 0.82005 -2.0799 0.217768 0.5112 -2.01656 0.247375 0.648986 2.02424 0.710947 0.56445 1.91917 0.980308 0.56232 1.95112 0.986698 -0 2.05147 0.702186 -0 1.93189 0.727388 0.77615 1.32545 0.681118 0.852 1.26952 0.988828 0.80514 1.73173 1.02078 0.7455 2.12791 0.330658 0.47712 2.16625 0.334918 -0 2.14495 0.285928 -0 2.11087 0.283798 0.4686 -1.89779 0.238642 0.77319 -1.8743 0.417775 0.78171 -1.79235 0.426508 0.82005 -1.79981 0.204988 0.82005 -0.338626 0.501058 0.8733 -0.338626 0.854638 0.83283 0.0767244 0.884733 0.8307 0.0831144 0.523561 0.87969 0.0809844 0.996173 0.75189 -0.334366 0.959008 0.75828 -1.17572 0.786478 0.81792 -1.17146 0.886588 0.769995 -1.79555 0.705538 0.75402 -1.48244 0.854638 0.76254 -1.87957 0.636313 0.755085 -1.99459 0.620338 0.63687 -1.92228 0.666133 0.61557 -1.79555 0.705538 0.75402 -1.99459 0.620338 0.63687 -2.10429 0.609688 0.43452 -2.0405 0.652288 0.44943 -1.18424 1.00587 0.67521 -1.22577 0.998413 0.61131 -0.332236 1.36371 0.522915 -0.325846 1.3488 0.567645 0.0724644 1.4534 0.525816 0.0724644 1.422 0.565089 -0.338626 1.36584 0.44091 0.0724644 1.4534 0.525816 0.0724644 1.422 0.565089 0.0724644 1.4534 0.525816 0.758324 1.44507 0.546345 0.758324 1.42207 0.568284 -1.69837 0.823497 0.672195 -1.65497 0.858898 0.67521 -1.79555 0.705538 0.75402 -1.17572 0.786478 0.81792 -1.77793 0.667889 0.791513 -1.77793 0.667889 0.791513 -1.87957 0.636313 0.755085 -1.92548 0.283372 0.75402 -2.01656 0.247375 0.648986 -2.02127 0.279538 0.648585 -1.91371 0.41671 0.76041 -2.09577 0.254404 0.53037 -2.08512 0.284224 0.54954 -2.09577 0.254404 0.53037 -2.11068 0.427786 0.48777 -2.10003 0.427786 0.52398 -2.0095 0.536203 0.646455 -1.99459 0.620338 0.63687 -1.87957 0.636313 0.755085 -1.90726 0.535138 0.75828 -2.10429 0.609688 0.43452 -2.0979 0.535138 0.50907 -2.10429 0.609688 0.43452 -1.99459 0.620338 0.63687 -2.0021 0.298708 0.648585 -1.99728 0.419053 0.648585 -1.98181 0.526618 0.648585 -2.0979 0.535138 0.50907 -2.0095 0.536203 0.646455 -1.98181 0.526618 0.648585 -1.90726 0.535138 0.75828 -1.90833 0.522358 0.74337 -1.90833 0.522358 0.74337 -1.90726 0.535138 0.75828 -1.91371 0.41671 0.76041 -1.91584 0.41458 0.7455 -1.92548 0.283372 0.75402 -1.934 0.300412 0.74124 -2.0021 0.298708 0.648585 -1.934 0.300412 0.74124 -1.92548 0.283372 0.75402 -2.02127 0.279538 0.648585 -2.08512 0.284224 0.54954 -1.99779 0.301264 0.47073 -2.0127 0.393706 0.44943 -2.11068 0.427786 0.48777 -2.09577 0.254404 0.53037 -2.0799 0.217768 0.5112 -2.09577 0.254404 0.53037 -2.01656 0.247375 0.648986 -1.87155 0.56453 0.780055 -1.77793 0.667889 0.791513 -1.77793 0.667889 0.791513 1.93189 0.727388 0.77615 1.95038 0.721298 0.74124 2.04197 0.617993 0.689055 1.99162 0.645798 0.75689 2.13287 0.612967 0.48564 2.04197 0.617993 0.689055 1.96816 0.298708 0.75828 2.0523 0.312553 0.654975 2.04165 0.263563 0.648585 1.89574 0.243418 0.77749 2.0523 0.312553 0.654975 2.13287 0.612967 0.48564 2.06897 0.621487 0.43878 2.07276 0.614856 -0.00213 2.17288 0.599946 -0 2.06897 0.621487 0.43878 2.13287 0.612967 0.48564 2.02424 0.710947 0.56445 2.06897 0.621487 0.43878 2.07276 0.614856 -0.00213 1.9213 1.13047 0.61344 1.24525 1.33502 0.595747 1.25247 1.35728 0.568904 1.25247 1.35728 0.568904 1.25247 1.35728 0.568904 1.25432 1.36468 0.532435 1.83114 1.18694 0.556371 1.9426 1.12941 0.56232 1.25678 1.39296 -0 0.776826 1.03165 0.737687 0.781045 0.943531 0.816262 0.0724644 1.422 0.565089 0.0732339 1.38393 0.58526 -0.326705 1.30968 0.595948 -0.325846 1.3488 0.567645 -1.18424 1.00587 0.67521 -0.589966 1.21248 0.629745 -0.871126 1.08042 0.677811 -1.13951 0.927058 0.740882 -1.12663 0.89058 0.770622 1.29273 1.07593 0.730956 1.40371 1.18692 0.660416 1.40371 1.21674 0.644733 1.2509 1.26793 0.634564 0.760556 1.37986 0.59096 0.436694 1.39566 0.582858 0.986234 1.34454 0.605104 -1.27345 0.99584 0.609727 -1.77105 0.847183 0.593205 -1.65497 0.858898 0.67521 -1.36468 0.992329 0.504638 -1.86158 0.801388 0.50268 -1.61723 0.451921 0.830215 -1.64432 0.315748 0.828903 -1.64429 0.200153 0.828914 -0.967871 0.491485 0.855431 -1.02254 0.573297 0.845117 -1.1407 0.652252 0.832709 -1.25457 0.674902 0.827382 -1.17572 0.786478 0.81792 -1.77793 0.667889 0.791513 -1.28009 0.679978 0.82467 -1.41947 0.652252 0.817775 -1.53764 0.573297 0.819437 -1.61659 0.455133 0.82987 -0.619366 0.947065 0.970881 -0.591112 0.947065 0.951823 -0.65543 0.925765 0.856467 -0.683684 0.925765 0.875525 -0.724377 0.927895 0.801022 -0.683684 0.925765 0.875525 -0.702513 0.92896 0.786225 -0.721058 0.888935 0.773473 -0.766319 0.883735 0.77568 -0.75736 0.845694 0.794984 -0.71447 0.852416 0.792656 -0.725887 0.94387 0.903594 -0.66948 0.96304 0.963254 -0.619366 1.05912 0.970881 -0.683684 1.07616 0.875525 -0.65543 1.07616 0.856467 -0.591112 1.05912 0.951823 -0.703578 1.07616 0.781965 -0.736092 1.07616 0.797827 -0.66948 1.04634 0.961124 -0.720562 1.05486 0.900399 -0.777322 1.05486 0.820499 -0.724377 0.927895 0.801022 -0.702513 0.92896 0.786225 -0.712602 1.008 0.771707 -0.740856 1.008 0.790764 -0.736092 1.07616 0.797827 -0.703578 1.07616 0.781965 -0.777322 1.05486 0.820499 -0.7903 1.008 0.824114 -0.780518 0.942805 0.823694 -0.725887 0.94387 0.903594 -0.780518 0.942805 0.823694 -0.7903 1.008 0.824114 -0.731157 1.008 0.907546 -0.720562 1.05486 0.900399 -0.777322 1.05486 0.820499 -0.66948 1.04634 0.961124 -0.668976 1.00693 0.973512 -0.66948 0.96304 0.963254 -0.619366 0.947065 0.970881 -0.614601 1.008 0.977944 -0.586348 1.008 0.958887 -0.591112 0.947065 0.951823 -0.591112 1.05912 0.951823 -0.619366 1.05912 0.970881 -0.619366 0.947065 0.970881 -0.66948 0.96304 0.963254 -0.668976 1.00693 0.973512 -0.614601 1.008 0.977944 -0.619366 1.05912 0.970881 -0.66948 1.04634 0.961124 -0.712856 0.890743 0.844192 -0.683684 0.925765 0.875525 -0.724377 0.927895 0.801022 -0.728894 0.91108 0.813996 -0.728894 0.91108 0.813996 -0.758395 0.911579 0.834925 -0.740324 0.89203 0.870733 -0.758395 0.911579 0.834925 -0.712856 0.890743 0.844192 -0.740324 0.89203 0.870733 -0.725887 0.94387 0.903594 -0.683684 0.925765 0.875525 0.771998 0.311382 0.860301 0.973454 0.315748 0.862142 0.973484 0.181558 0.837 0.774923 0.181558 0.837 0.0767244 0.181558 0.837 0.078842 0.314892 0.861176 -0.338626 0.317006 0.859697 -0.338626 0.181558 0.837 -0.943581 0.455133 0.856121 -0.915882 0.187412 0.832316 -0.915856 0.315748 0.847317 2.17792 0.40139 -0 2.13904 0.395036 0.479063 2.13287 0.612967 0.48564 2.17288 0.599946 -0 2.05995 0.382107 0.662736 2.0523 0.312553 0.654975 2.04197 0.617993 0.689055 1.96816 0.298708 0.75828 1.98493 0.369027 0.760947 1.98493 0.369027 0.760947 1.99162 0.645798 0.75689 2.04197 0.617993 0.689055 1.92016 0.35844 0.788499 1.98493 0.369027 0.760947 1.89574 0.243418 0.77749 1.98493 0.369027 0.760947 1.70191 0.315748 0.811085 1.67419 0.455133 0.811591 1.59523 0.573297 0.817803 1.47707 0.652252 0.830695 1.33768 0.679978 0.850203 1.32551 0.677556 0.852 1.70189 0.227264 0.797316 1.1983 0.652252 0.858539 0.977256 0.961726 0.811795 0.977256 0.961726 0.811795 0.984991 1.04967 0.73648 0.781045 0.943531 0.816262 0.781045 0.943531 0.816262 0.764764 0.562972 0.880827 1.00118 0.455133 0.857038 1.08013 0.573297 0.860471 -1.95859 0.799416 0.27 -2.02428 0.735358 0.27 -2.06925 0.735358 -0 -2.00468 0.797128 -0 -1.97234 0.735358 0.476055 -1.48283 0.990212 -0 -1.45673 0.991344 0.27 -2.13362 0.258586 0.27 -2.1196 0.22229 0.27 -2.16404 0.227353 -0 -2.17288 0.262924 -0 -2.09577 0.254404 0.53037 -2.0799 0.217768 0.5112 -2.1375 0.430163 0.27 -2.12945 0.607268 0.27 -2.10429 0.609688 0.43452 -2.17074 0.433111 -0 -2.17074 0.603298 -0 -2.08536 0.655689 0.27 -2.12783 0.660808 -0 -2.1375 0.430163 0.27 -2.04668 0.394131 0.27 -2.07276 0.394771 -0 -2.17074 0.433111 -0 -2.11068 0.427786 0.48777 -2.0127 0.393706 0.44943 -2.03976 0.297631 0.27 -2.13362 0.258586 0.27 -2.17288 0.262924 -0 -2.07276 0.292744 -0 -2.09577 0.254404 0.53037 -1.99779 0.301264 0.47073 -2.12945 0.607268 0.27 -2.17074 0.603298 -0 1.73173 1.02078 -0.7455 1.88722 1.11876 -0.64326 1.26633 1.07403 -0.73485 1.26952 0.988828 -0.80514 -0.346882 1.36914 -0.27 0.758324 1.45743 -0.51546 0.0767244 1.46264 -0.485052 -1.89779 0.238642 -0.77319 -2.01656 0.247375 -0.648986 -2.0799 0.217768 -0.5112 -1.79981 0.204988 -0.82005 2.02424 0.710947 -0.56445 1.91917 0.980308 -0.56232 1.93189 0.727388 -0.77615 1.73173 1.02078 -0.7455 1.26952 0.988828 -0.80514 1.32545 0.681118 -0.852 2.12791 0.330658 -0.47712 2.11087 0.283798 -0.4686 -1.89779 0.238642 -0.77319 -1.79981 0.204988 -0.82005 -1.79235 0.426508 -0.82005 -1.8743 0.417775 -0.78171 -0.338626 0.501058 -0.8733 0.0831144 0.523561 -0.87969 0.0767244 0.884733 -0.8307 -0.338626 0.854638 -0.83283 0.0809844 0.996173 -0.75189 -0.334366 0.959008 -0.75828 -1.17146 0.886588 -0.769995 -1.17572 0.786478 -0.81792 -1.48244 0.854638 -0.76254 -1.79555 0.705538 -0.75402 -1.87957 0.636313 -0.755085 -1.79555 0.705538 -0.75402 -1.92228 0.666133 -0.61557 -1.99459 0.620338 -0.63687 -1.99459 0.620338 -0.63687 -2.0405 0.652288 -0.44943 -2.10429 0.609688 -0.43452 -1.18424 1.00587 -0.67521 -0.325846 1.3488 -0.567645 -0.332236 1.36371 -0.522915 -1.22577 0.998413 -0.61131 0.0724644 1.422 -0.565089 0.0724644 1.4534 -0.525816 0.0724644 1.4534 -0.525816 -0.338626 1.36584 -0.44091 0.0724644 1.422 -0.565089 0.758324 1.42207 -0.568284 0.758324 1.44507 -0.546345 0.0724644 1.4534 -0.525816 -1.69837 0.823497 -0.672195 -1.65497 0.858898 -0.67521 -1.79555 0.705538 -0.75402 -1.77793 0.667889 -0.791513 -1.17572 0.786478 -0.81792 -1.77793 0.667889 -0.791513 -1.87957 0.636313 -0.755085 -1.92548 0.283372 -0.75402 -2.02127 0.279538 -0.648585 -2.01656 0.247375 -0.648986 -1.91371 0.41671 -0.76041 -2.08512 0.284224 -0.54954 -2.09577 0.254404 -0.53037 -2.10003 0.427786 -0.52398 -2.11068 0.427786 -0.48777 -2.09577 0.254404 -0.53037 -2.0095 0.536203 -0.646455 -1.90726 0.535138 -0.75828 -1.87957 0.636313 -0.755085 -1.99459 0.620338 -0.63687 -2.0979 0.535138 -0.50907 -2.10429 0.609688 -0.43452 -1.99459 0.620338 -0.63687 -2.10429 0.609688 -0.43452 -2.0021 0.298708 -0.648585 -1.99728 0.419053 -0.648585 -1.98181 0.526618 -0.648585 -2.0979 0.535138 -0.50907 -1.98181 0.526618 -0.648585 -2.0095 0.536203 -0.646455 -1.90833 0.522358 -0.74337 -1.90726 0.535138 -0.75828 -1.90833 0.522358 -0.74337 -1.91584 0.41458 -0.7455 -1.91371 0.41671 -0.76041 -1.90726 0.535138 -0.75828 -1.934 0.300412 -0.74124 -1.92548 0.283372 -0.75402 -2.0021 0.298708 -0.648585 -2.02127 0.279538 -0.648585 -1.92548 0.283372 -0.75402 -1.934 0.300412 -0.74124 -2.08512 0.284224 -0.54954 -1.99779 0.301264 -0.47073 -2.09577 0.254404 -0.53037 -2.11068 0.427786 -0.48777 -2.0127 0.393706 -0.44943 -2.0799 0.217768 -0.5112 -2.01656 0.247375 -0.648986 -2.09577 0.254404 -0.53037 -1.87155 0.56453 -0.780055 -1.77793 0.667889 -0.791513 -1.77793 0.667889 -0.791513 1.93189 0.727388 -0.77615 1.99162 0.645798 -0.75689 2.04197 0.617993 -0.689055 1.95038 0.721298 -0.74124 2.04197 0.617993 -0.689055 2.13287 0.612967 -0.48564 1.96816 0.298708 -0.75828 1.89574 0.243418 -0.77749 2.04165 0.263563 -0.648585 2.0523 0.312553 -0.654975 2.0523 0.312553 -0.654975 2.13287 0.612967 -0.48564 2.07276 0.614856 0.00213 2.06897 0.621487 -0.43878 2.06897 0.621487 -0.43878 2.02424 0.710947 -0.56445 2.13287 0.612967 -0.48564 2.06897 0.621487 -0.43878 2.07276 0.614856 0.00213 1.9213 1.13047 -0.61344 1.25247 1.35728 -0.568904 1.24525 1.33502 -0.595747 1.25247 1.35728 -0.568904 1.9426 1.12941 -0.56232 1.83114 1.18694 -0.556371 1.25432 1.36468 -0.532435 1.25247 1.35728 -0.568904 0.781045 0.943531 -0.816262 0.776826 1.03165 -0.737687 0.0724644 1.422 -0.565089 -0.325846 1.3488 -0.567645 -0.326705 1.30968 -0.595948 0.0732339 1.38393 -0.58526 -1.18424 1.00587 -0.67521 -1.12663 0.89058 -0.770622 -1.13951 0.927058 -0.740882 -0.871126 1.08042 -0.677811 -0.589966 1.21248 -0.629745 1.2509 1.26793 -0.634564 1.40371 1.21674 -0.644733 1.40371 1.18692 -0.660416 1.29273 1.07593 -0.730956 0.436694 1.39566 -0.582858 0.760556 1.37986 -0.59096 0.986234 1.34454 -0.605104 -1.27345 0.99584 -0.609727 -1.77105 0.847183 -0.593205 -1.65497 0.858898 -0.67521 -1.36468 0.992329 -0.504638 -1.86158 0.801388 -0.50268 -1.64429 0.200153 -0.828914 -1.64432 0.315748 -0.828903 -1.61723 0.451921 -0.830215 -1.17572 0.786478 -0.81792 -1.25457 0.674902 -0.827382 -1.1407 0.652252 -0.832709 -1.02254 0.573297 -0.845117 -0.967871 0.491485 -0.855431 -1.77793 0.667889 -0.791513 -1.61659 0.455133 -0.82987 -1.53764 0.573297 -0.819437 -1.41947 0.652252 -0.817775 -1.28009 0.679978 -0.82467 -0.619366 0.947065 -0.970881 -0.683684 0.925765 -0.875525 -0.65543 0.925765 -0.856467 -0.591112 0.947065 -0.951823 -0.724377 0.927895 -0.801022 -0.702513 0.92896 -0.786225 -0.683684 0.925765 -0.875525 -0.721058 0.888935 -0.773473 -0.71447 0.852416 -0.792656 -0.75736 0.845694 -0.794984 -0.766319 0.883735 -0.77568 -0.66948 0.96304 -0.963254 -0.725887 0.94387 -0.903594 -0.619366 1.05912 -0.970881 -0.591112 1.05912 -0.951823 -0.65543 1.07616 -0.856467 -0.683684 1.07616 -0.875525 -0.703578 1.07616 -0.781965 -0.736092 1.07616 -0.797827 -0.720562 1.05486 -0.900399 -0.66948 1.04634 -0.961124 -0.777322 1.05486 -0.820499 -0.724377 0.927895 -0.801022 -0.740856 1.008 -0.790764 -0.712602 1.008 -0.771707 -0.702513 0.92896 -0.786225 -0.736092 1.07616 -0.797827 -0.703578 1.07616 -0.781965 -0.7903 1.008 -0.824114 -0.777322 1.05486 -0.820499 -0.780518 0.942805 -0.823694 -0.725887 0.94387 -0.903594 -0.731157 1.008 -0.907546 -0.7903 1.008 -0.824114 -0.780518 0.942805 -0.823694 -0.720562 1.05486 -0.900399 -0.777322 1.05486 -0.820499 -0.668976 1.00693 -0.973512 -0.66948 1.04634 -0.961124 -0.66948 0.96304 -0.963254 -0.619366 0.947065 -0.970881 -0.591112 0.947065 -0.951823 -0.586348 1.008 -0.958887 -0.614601 1.008 -0.977944 -0.591112 1.05912 -0.951823 -0.619366 1.05912 -0.970881 -0.619366 0.947065 -0.970881 -0.614601 1.008 -0.977944 -0.668976 1.00693 -0.973512 -0.66948 0.96304 -0.963254 -0.619366 1.05912 -0.970881 -0.66948 1.04634 -0.961124 -0.712856 0.890743 -0.844192 -0.728894 0.91108 -0.813996 -0.724377 0.927895 -0.801022 -0.683684 0.925765 -0.875525 -0.728894 0.91108 -0.813996 -0.758395 0.911579 -0.834925 -0.740324 0.89203 -0.870733 -0.758395 0.911579 -0.834925 -0.712856 0.890743 -0.844192 -0.683684 0.925765 -0.875525 -0.725887 0.94387 -0.903594 -0.740324 0.89203 -0.870733 0.771998 0.311382 -0.860301 0.774923 0.181558 -0.837 0.973484 0.181558 -0.837 0.973454 0.315748 -0.862142 0.0767244 0.181558 -0.837 0.078842 0.314892 -0.861176 -0.338626 0.317006 -0.859697 -0.338626 0.181558 -0.837 -0.943581 0.455133 -0.856121 -0.915856 0.315748 -0.847317 -0.915882 0.187412 -0.832316 2.13904 0.395036 -0.479063 2.13287 0.612967 -0.48564 2.05995 0.382107 -0.662736 2.0523 0.312553 -0.654975 2.04197 0.617993 -0.689055 1.98493 0.369027 -0.760947 1.96816 0.298708 -0.75828 1.98493 0.369027 -0.760947 2.04197 0.617993 -0.689055 1.99162 0.645798 -0.75689 1.92016 0.35844 -0.788499 1.98493 0.369027 -0.760947 1.89574 0.243418 -0.77749 1.98493 0.369027 -0.760947 1.32551 0.677556 -0.852 1.33768 0.679978 -0.850203 1.47707 0.652252 -0.830695 1.59523 0.573297 -0.817803 1.67419 0.455133 -0.811591 1.70191 0.315748 -0.811085 1.70189 0.227264 -0.797316 1.1983 0.652252 -0.858539 0.977256 0.961726 -0.811795 0.977256 0.961726 -0.811795 0.984991 1.04967 -0.73648 0.781045 0.943531 -0.816262 0.764764 0.562972 -0.880827 0.781045 0.943531 -0.816262 1.00118 0.455133 -0.857038 1.08013 0.573297 -0.860471 -1.95859 0.799416 -0.27 -2.02428 0.735358 -0.27 -1.97234 0.735358 -0.476055 -1.45673 0.991344 -0.27 -2.13362 0.258586 -0.27 -2.1196 0.22229 -0.27 -2.09577 0.254404 -0.53037 -2.0799 0.217768 -0.5112 -2.10429 0.609688 -0.43452 -2.12945 0.607268 -0.27 -2.1375 0.430163 -0.27 -2.08536 0.655689 -0.27 -2.1375 0.430163 -0.27 -2.04668 0.394131 -0.27 -2.11068 0.427786 -0.48777 -2.0127 0.393706 -0.44943 -2.03976 0.297631 -0.27 -2.13362 0.258586 -0.27 -2.09577 0.254404 -0.53037 -1.99779 0.301264 -0.47073 -2.12945 0.607268 -0.27 + + + + + + + + + + 0.0464713 0.684961 0.727096 0.00162414 0.669333 0.74296 0.00162414 0.669333 0.74296 0.125971 0.66188 0.73895 -0.148141 0.988966 -0 -0.224544 0.97411 0.0262542 -0.222613 0.974907 -0 0.0800996 0.98932 0.121781 -0.108723 0.991351 0.0735049 0.0700425 0.997544 -0 -0.458294 -0.802598 0.381841 -0.458294 -0.802598 0.381841 -0.596247 -0.683932 0.420388 -0.596247 -0.683932 0.420388 0.881742 0.457881 0.113474 0.930814 0.363378 0.0392565 0.931532 0.363658 -0 0.914182 0.405304 -0 0.208922 0.0756295 0.975003 0.0820383 0.122177 0.989112 0.0617949 0.168184 0.983817 0.10889 0.176486 0.978262 0.946326 -0.231035 0.226029 0.964465 -0.264211 -0 0.935517 -0.353283 -0 0.928372 -0.301155 0.217788 -0.580444 -0.0480189 0.812883 -0.433975 0.0428938 0.899903 -0.206029 0.0671512 0.976239 -0.247542 0.00766538 0.968847 -0.0219955 0.0131531 0.999672 -0.0325852 0.358157 0.933092 -0.026097 0.361885 0.931857 -0.0100734 0.0197279 0.999755 -0.0353519 0.577941 0.815313 -0.0390718 0.579904 0.813747 -0.0746195 0.394249 0.915969 -0.109626 0.558028 0.822549 -0.222558 0.55059 0.804561 -0.221155 0.49179 0.842159 -0.502765 0.619554 0.602811 -0.620344 0.676035 0.397682 -0.526021 0.780436 0.337967 -0.393916 0.642068 0.657708 -0.526021 0.780436 0.337967 -0.526299 0.829588 0.186532 -0.622647 0.758232 0.193379 -0.234512 0.966385 0.105378 -0.20656 0.978227 0.020137 -0.249314 0.953765 0.167855 -0.264262 0.936573 0.230209 -0.0986946 0.943907 0.315118 -0.0871377 0.869011 0.487059 -0.22153 0.974609 0.0325669 -0.128082 0.971081 0.201485 -0.067129 0.695866 0.715027 -0.0565828 0.914035 0.40167 0.0720297 0.895568 0.439055 0.0351075 0.63862 0.768721 -0.401017 0.422431 0.812858 -0.2969 0.515678 0.803695 -0.316722 0.600888 0.733908 -0.0896266 0.561919 0.822322 -0.336328 0.494446 0.801503 -0.321745 0.407768 0.854521 -0.567549 0.390617 0.72478 -0.649833 -0.0782596 0.756037 -0.778067 -0.280744 0.561956 -0.785347 -0.140733 0.602847 -0.517873 0.0142206 0.85534 -0.832843 -0.227187 0.504736 -0.829872 -0.0296573 0.557165 -0.856316 -0.0597696 0.512981 -0.952374 0.0423695 0.301975 -0.852939 0.0495512 0.519653 -0.750202 0.316124 0.580743 -0.750202 0.316124 0.580743 -0.554003 0.303887 0.77507 -0.614397 0.140578 0.776373 -0.932625 0.189677 0.306976 -0.852168 0.202532 0.482483 -0.88459 0.247042 0.395565 -0.702489 0.451421 0.550207 -0.768242 0.0307639 0.639419 -0.766265 0.0703072 0.638666 -0.763087 0.10974 0.636911 -0.334153 -0.915977 0.222098 -0.334166 -0.916483 0.219983 -0.334166 -0.916483 0.219983 -0.334176 -0.916984 0.217868 -0.334176 -0.916984 0.217868 -0.997501 0.0697151 0.0114952 -0.997501 0.0697151 0.0114952 -0.991689 0.11094 0.0651592 -0.991689 0.11094 0.0651592 -0.981302 0.151653 0.118523 -0.981302 0.151653 0.118523 -0.632968 0.63296 0.445773 -0.630744 0.630736 0.452034 -0.630744 0.630736 0.452034 -0.632968 0.63296 0.445773 -0.635161 0.635153 0.439491 -0.404774 -0.266812 -0.874625 -0.404774 -0.266812 -0.874625 -0.404774 -0.266812 -0.874625 -0.404774 -0.266812 -0.874625 -0.712451 -0.620266 0.328153 -0.842317 -0.381921 0.380314 -0.725226 -0.430572 0.537266 -0.445276 0.153208 0.882188 -0.27319 0.353694 0.894577 -0.29619 0.268123 0.916723 0.796453 0.504292 0.333694 0.790575 0.525262 0.314786 0.857976 0.369633 0.35672 0.796453 0.504292 0.333694 0.78404 0.545795 0.295617 0.790575 0.525262 0.314786 0.619108 -0.66678 0.414861 0.786525 -0.470464 0.400053 0.786525 -0.470464 0.400053 0.619108 -0.66678 0.414861 0.831978 -0.312679 0.458305 0.142784 0.989644 -0.014772 0.142784 0.989644 -0.014772 0.142784 0.989644 -0.014772 0.1428 0.989752 -0 0.417752 0.803814 -0.423516 0.417752 0.803814 -0.423516 0.417752 0.803814 -0.423516 0.894986 0.446094 0.000995305 0.894986 0.446094 0.000995305 0.279499 0.893335 0.351898 0.119853 0.64295 0.756472 0.211995 0.892472 0.398186 0.173007 0.855625 0.487827 0.244343 0.92112 0.30304 0.207042 0.970519 0.123397 0.312559 0.943441 0.110576 0.312559 0.943441 0.110576 0.132432 0.991192 -0 -0.0423706 0.62151 0.782259 -0.020109 0.399352 0.916577 -0.0295698 0.584281 0.811013 -0.04205 0.469609 0.881873 -0.112485 0.53807 0.835361 -0.112485 0.53807 0.835361 -0.165585 0.602611 0.780668 -0.144132 0.606127 0.7822 -0.144132 0.606127 0.7822 -0.144132 0.606127 0.7822 -0.144132 0.606127 0.7822 0.0949568 0.474177 0.875294 0.0949568 0.474177 0.875294 0.0949568 0.474177 0.875294 0.0681183 0.488787 0.86974 0.0185385 0.4882 0.872535 -0.00415225 0.473076 0.881012 0.0412142 0.502926 0.863347 -0.232367 0.959996 0.156248 -0.315203 0.909625 0.270608 -0.283817 0.91998 0.270342 -0.350933 0.914074 0.203262 -0.415421 0.88529 0.209014 -0.0628664 0.0616415 0.996117 -0.0582331 0.00195977 0.998301 -0.0582331 0.00195977 0.998301 -0.0277108 0.0569298 0.997994 -0.0269456 0.113674 0.993153 -0.0269456 0.113674 0.993153 -0.0471199 0.117413 0.991965 -0.0510148 0.32 0.946043 -0.244049 0.172627 0.954275 -0.0672742 0.121102 0.990358 -0.0672742 0.121102 0.990358 -0.0672742 0.121102 0.990358 -0.0672742 0.121102 0.990358 -0.0394169 -0.969205 0.243081 0.101823 -0.983282 0.150959 0.0619551 -0.996526 0.0556529 0.0956494 -0.966236 0.239249 0.0214154 -0.99896 -0.0402564 -0.0191261 -0.98863 0.149145 0.0214154 -0.99896 -0.0402564 0.0100696 -0.463573 -0.886002 0.0100696 -0.463573 -0.886002 0.0100696 -0.463573 -0.886002 0.0100696 -0.463573 -0.886002 -0.179528 -0.927376 0.328244 -0.179528 -0.927376 0.328244 -0.101924 0.965105 0.241212 -0.139107 0.973742 0.180209 0.0410855 0.997297 0.0609119 0.081949 0.989203 0.121494 0 1 -0 -0.175507 0.977335 0.118381 -0.280831 0.893985 0.349177 -0.312649 0.904214 0.290942 -0.343058 0.910367 0.231396 -0.498002 -0.2822 -0.819974 -0.540135 -0.21531 -0.81357 -0.495861 -0.0470105 -0.867128 -0.486151 -0.0424564 -0.872843 -0.481497 0.123575 -0.867692 -0.435147 0.122848 -0.891939 -0.526529 0.123964 -0.841071 -0.476385 -0.0379032 -0.878419 -0.475506 -0.315347 -0.821249 -0.81622 -0.077713 0.57249 -0.862389 -0.0650725 0.502046 -0.817388 0.081867 0.570241 -0.773621 0.081756 0.628352 -0.75454 0.262341 0.601537 -0.786518 0.263045 0.558745 -0.720409 0.260888 0.642611 -0.725759 0.0812124 0.683138 -0.706467 -0.101221 0.70047 0.553805 -0.138479 0.82105 0.559145 0.013111 0.828966 0.559145 0.013111 0.828966 0.553805 -0.138479 0.82105 0.551584 0.164399 0.817758 0.551584 0.164399 0.817758 -0.180584 -0.0993123 0.978533 -0.180584 -0.0993123 0.978533 -0.200326 0.00721103 0.979703 -0.200326 0.00721103 0.979703 -0.217715 0.11365 0.969373 -0.217715 0.11365 0.969373 0.81264 -0.181425 -0.553806 0.81264 -0.181425 -0.553806 0.81264 -0.181425 -0.553806 0.81264 -0.181425 -0.553806 -0.52851 -0.425032 -0.734864 -0.52851 -0.425032 -0.734864 -0.898407 -0.0276176 0.438296 -0.898407 -0.0276176 0.438296 0.42093 -0.773927 0.473133 0.42093 -0.773927 0.473133 0.42093 -0.773927 0.473133 0.269929 -0.907353 0.322256 0.0149237 -0.129156 0.991512 0.0294287 -0.128276 0.991302 -0.00516663 -0.176765 0.98424 -0.00258333 -0.177588 0.984102 -0.00216605 -0.171839 0.985123 -0.00347153 -0.128408 0.991715 -0.0117901 -0.123207 0.992311 -0.00700485 -0.165258 0.986225 -0.0255699 -0.0368704 0.998993 -0.00967764 -0.165254 0.986203 -0.0162158 -0.119602 0.992689 0.99727 -0.0738441 -0 0.968039 -0.0675461 0.241534 0.96845 0.025314 0.247918 0.999666 0.0258599 -0 0.858651 -0.071496 0.507549 0.871636 -0.181502 0.455311 0.866433 0.179212 0.466022 0.592063 -0.165143 0.78879 0.668775 -0.113662 0.734725 0.674834 -0.0500719 0.736269 0.612746 0.0041994 0.790269 0.860007 0.0069367 0.510235 0.254553 -0.0605103 0.965164 0.535983 -0.054446 0.842471 0.249464 -0.144612 0.957525 0.528332 -0.103657 0.842687 0.124053 -0.0459156 0.991213 0.12185 0.029334 0.992115 0.12185 0.029334 0.992115 0.12185 0.029334 0.992115 0.12185 0.029334 0.992115 0.12185 0.029334 0.992115 0.125553 -0.120905 0.984692 0.0326569 0.0845848 0.995881 0.0154701 0.163029 0.9865 -0.0481555 0.657622 0.751807 -0.0481555 0.657622 0.751807 -0.0423706 0.62151 0.782259 -0.00838985 0.300173 0.953848 0.0278152 0.0133351 0.999524 0.0651534 -0.0766469 0.994927 0.0663879 -0.0739671 0.995049 -0.491088 0.861183 0.131133 -0.709033 0.685211 0.166605 -0.747759 0.66397 -3.7631e-09 -0.533771 0.845629 -0 -0.672764 0.709103 0.211096 -0.34701 0.937861 -0 -0.35056 0.931894 0.0931746 -0.906623 -0.402898 0.125334 -0.906623 -0.402898 0.125334 -0.932794 -0.360411 -0 -0.932794 -0.360411 -0 -0.814465 -0.503577 0.288198 -0.814465 -0.503577 0.288198 -0.988946 0.0577864 0.136555 -0.988946 0.0577864 0.136555 -0.977074 0.0646214 0.202857 -0.99897 0.0453806 -0 -0.99897 0.0453806 -0 -0.72623 0.669673 0.155328 -0.76719 0.64142 -0 -0.343553 -0.938586 0.0320598 -0.343553 -0.938586 0.0320598 -0.368792 -0.929512 -0 -0.368792 -0.929512 -0 -0.318294 -0.947553 0.0288515 -0.318294 -0.947553 0.0288515 -0.389195 0.919735 0.0511449 -0.389195 0.919735 0.0511449 -0.384073 0.923303 -0 -0.384073 0.923303 -0 -0.394307 0.916151 0.0720423 -0.394307 0.916151 0.0720423 -0.657201 0.739803 0.144147 -0.739402 0.673264 -0 0.0464713 0.684961 -0.727096 0.125971 0.66188 -0.73895 0.00162414 0.669333 -0.74296 0.00162414 0.669333 -0.74296 -0.224544 0.97411 -0.0262542 0.0800996 0.98932 -0.121781 -0.108723 0.991351 -0.0735049 -0.458294 -0.802598 -0.381841 -0.596247 -0.683932 -0.420388 -0.596247 -0.683932 -0.420388 -0.458294 -0.802598 -0.381841 0.881742 0.457881 -0.113474 0.930814 0.363378 -0.0392565 0.208922 0.0756295 -0.975003 0.10889 0.176486 -0.978262 0.0617949 0.168184 -0.983817 0.0820383 0.122177 -0.989112 0.946326 -0.231035 -0.226029 0.928372 -0.301155 -0.217788 -0.580444 -0.0480189 -0.812883 -0.247542 0.00766538 -0.968847 -0.206029 0.0671512 -0.976239 -0.433975 0.0428938 -0.899903 -0.0219955 0.0131531 -0.999672 -0.0100734 0.0197279 -0.999755 -0.026097 0.361885 -0.931857 -0.0325852 0.358157 -0.933092 -0.0353519 0.577941 -0.815313 -0.0390718 0.579904 -0.813747 -0.109626 0.558028 -0.822549 -0.0746195 0.394249 -0.915969 -0.221155 0.49179 -0.842159 -0.222558 0.55059 -0.804561 -0.502765 0.619554 -0.602811 -0.393916 0.642068 -0.657708 -0.526021 0.780436 -0.337967 -0.620344 0.676035 -0.397682 -0.526021 0.780436 -0.337967 -0.622647 0.758232 -0.193379 -0.526299 0.829588 -0.186532 -0.234512 0.966385 -0.105378 -0.264262 0.936573 -0.230209 -0.249314 0.953765 -0.167855 -0.20656 0.978227 -0.020137 -0.0871377 0.869011 -0.487059 -0.0986946 0.943907 -0.315118 -0.128082 0.971081 -0.201485 -0.22153 0.974609 -0.0325669 -0.067129 0.695866 -0.715027 0.0351075 0.63862 -0.768721 0.0720297 0.895568 -0.439055 -0.0565828 0.914035 -0.40167 -0.401017 0.422431 -0.812858 -0.2969 0.515678 -0.803695 -0.316722 0.600888 -0.733908 -0.336328 0.494446 -0.801503 -0.0896266 0.561919 -0.822322 -0.321745 0.407768 -0.854521 -0.567549 0.390617 -0.72478 -0.649833 -0.0782596 -0.756037 -0.785347 -0.140733 -0.602847 -0.778067 -0.280744 -0.561956 -0.517873 0.0142206 -0.85534 -0.829872 -0.0296573 -0.557165 -0.832843 -0.227187 -0.504737 -0.852939 0.0495512 -0.519653 -0.952374 0.0423695 -0.301975 -0.856316 -0.0597696 -0.512981 -0.750202 0.316124 -0.580743 -0.614397 0.140578 -0.776373 -0.554003 0.303887 -0.77507 -0.750202 0.316124 -0.580743 -0.852168 0.202532 -0.482483 -0.932625 0.189677 -0.306976 -0.702489 0.451421 -0.550207 -0.88459 0.247042 -0.395565 -0.768242 0.0307639 -0.639419 -0.766265 0.0703072 -0.638666 -0.763087 0.10974 -0.636911 -0.334153 -0.915977 -0.222098 -0.334166 -0.916483 -0.219983 -0.334166 -0.916483 -0.219983 -0.334176 -0.916984 -0.217868 -0.334176 -0.916984 -0.217868 -0.997501 0.0697151 -0.0114952 -0.991689 0.11094 -0.0651592 -0.991689 0.11094 -0.0651592 -0.997501 0.0697151 -0.0114952 -0.981302 0.151653 -0.118523 -0.981302 0.151653 -0.118523 -0.632968 0.63296 -0.445773 -0.632968 0.63296 -0.445773 -0.630744 0.630736 -0.452034 -0.630744 0.630736 -0.452034 -0.635161 0.635153 -0.439491 -0.404774 -0.266812 0.874625 -0.404774 -0.266812 0.874625 -0.404774 -0.266812 0.874625 -0.404774 -0.266812 0.874625 -0.712451 -0.620266 -0.328153 -0.725226 -0.430572 -0.537266 -0.842317 -0.381921 -0.380314 -0.445276 0.153208 -0.882188 -0.27319 0.353694 -0.894577 -0.29619 0.268123 -0.916723 0.796453 0.504292 -0.333694 0.796453 0.504292 -0.333694 0.857976 0.369633 -0.35672 0.790575 0.525262 -0.314786 0.790575 0.525262 -0.314786 0.78404 0.545795 -0.295617 0.619108 -0.66678 -0.414861 0.619108 -0.66678 -0.414861 0.786525 -0.470464 -0.400053 0.786525 -0.470464 -0.400053 0.831978 -0.312679 -0.458305 0.142784 0.989644 0.014772 0.142784 0.989644 0.014772 0.142784 0.989644 0.014772 0.417752 0.803814 0.423516 0.417752 0.803814 0.423516 0.417752 0.803814 0.423516 0.894986 0.446094 -0.000995305 0.894986 0.446094 -0.000995305 0.279499 0.893335 -0.351898 0.211995 0.892472 -0.398186 0.119853 0.64295 -0.756472 0.173007 0.855625 -0.487827 0.312559 0.943441 -0.110576 0.312559 0.943441 -0.110576 0.207042 0.970519 -0.123397 0.244343 0.92112 -0.30304 -0.020109 0.399352 -0.916577 -0.0423706 0.62151 -0.782259 -0.0295698 0.584281 -0.811013 -0.112485 0.53807 -0.835361 -0.112485 0.53807 -0.835361 -0.04205 0.469609 -0.881873 -0.165585 0.602611 -0.780668 -0.144132 0.606127 -0.7822 -0.144132 0.606127 -0.7822 -0.144132 0.606127 -0.7822 -0.144132 0.606127 -0.7822 0.0681183 0.488787 -0.86974 0.0949568 0.474177 -0.875294 0.0949568 0.474177 -0.875294 0.0949568 0.474177 -0.875294 -0.00415225 0.473076 -0.881012 0.0185385 0.4882 -0.872535 0.0412142 0.502926 -0.863347 -0.232367 0.959996 -0.156248 -0.315203 0.909625 -0.270608 -0.283817 0.91998 -0.270342 -0.350933 0.914074 -0.203262 -0.415421 0.88529 -0.209014 -0.0582331 0.00195977 -0.998301 -0.0582331 0.00195977 -0.998301 -0.0628664 0.0616415 -0.996117 -0.0510148 0.32 -0.946043 -0.0471199 0.117413 -0.991965 -0.0269456 0.113674 -0.993153 -0.0269456 0.113674 -0.993153 -0.0277108 0.0569298 -0.997994 -0.244049 0.172627 -0.954275 -0.0672742 0.121102 -0.990358 -0.0672742 0.121102 -0.990358 -0.0672742 0.121102 -0.990358 -0.0672742 0.121102 -0.990358 -0.0394169 -0.969205 -0.243081 0.0956494 -0.966236 -0.239249 0.0619551 -0.996526 -0.0556529 0.101823 -0.983282 -0.150959 0.0214154 -0.99896 0.0402564 0.0214154 -0.99896 0.0402564 -0.0191261 -0.98863 -0.149145 0.0100696 -0.463573 0.886002 0.0100696 -0.463573 0.886002 0.0100696 -0.463573 0.886002 0.0100696 -0.463573 0.886002 -0.179528 -0.927376 -0.328244 -0.179528 -0.927376 -0.328244 -0.101924 0.965105 -0.241212 0.081949 0.989203 -0.121494 0.0410855 0.997297 -0.0609119 -0.139107 0.973742 -0.180209 0 1 -0 -0.175507 0.977335 -0.118381 -0.312649 0.904214 -0.290942 -0.280831 0.893985 -0.349177 -0.343058 0.910367 -0.231396 -0.498002 -0.2822 0.819974 -0.486151 -0.0424564 0.872843 -0.495861 -0.0470105 0.867128 -0.540135 -0.21531 0.81357 -0.481497 0.123575 0.867692 -0.435147 0.122848 0.891939 -0.476385 -0.0379032 0.878419 -0.526529 0.123964 0.841071 -0.475506 -0.315347 0.821249 -0.81622 -0.077713 -0.57249 -0.773621 0.081756 -0.628352 -0.817388 0.081867 -0.570241 -0.862389 -0.0650725 -0.502046 -0.75454 0.262341 -0.601537 -0.786518 0.263045 -0.558745 -0.725759 0.0812124 -0.683138 -0.720409 0.260888 -0.642611 -0.706467 -0.101221 -0.70047 0.553805 -0.138479 -0.82105 0.553805 -0.138479 -0.82105 0.559145 0.013111 -0.828966 0.559145 0.013111 -0.828966 0.551584 0.164399 -0.817758 0.551584 0.164399 -0.817758 -0.180584 -0.0993123 -0.978533 -0.200326 0.00721103 -0.979703 -0.200326 0.00721103 -0.979703 -0.180584 -0.0993123 -0.978533 -0.217715 0.11365 -0.969373 -0.217715 0.11365 -0.969373 0.81264 -0.181425 0.553806 0.81264 -0.181425 0.553806 0.81264 -0.181425 0.553806 0.81264 -0.181425 0.553806 -0.52851 -0.425032 0.734864 -0.52851 -0.425032 0.734864 -0.898407 -0.0276176 -0.438296 -0.898407 -0.0276176 -0.438296 0.42093 -0.773927 -0.473133 0.269929 -0.907353 -0.322256 0.42093 -0.773927 -0.473133 0.42093 -0.773927 -0.473133 0.0149237 -0.129156 -0.991512 -0.00258333 -0.177588 -0.984102 -0.00516663 -0.176765 -0.98424 0.0294287 -0.128276 -0.991302 -0.00216605 -0.171839 -0.985123 -0.00347153 -0.128408 -0.991715 -0.0117901 -0.123208 -0.992311 -0.00700485 -0.165258 -0.986225 -0.0255699 -0.0368704 -0.998993 -0.0162158 -0.119602 -0.992689 -0.00967764 -0.165254 -0.986203 0.968039 -0.0675461 -0.241534 0.96845 0.025314 -0.247918 0.858651 -0.071496 -0.507549 0.871636 -0.181502 -0.455311 0.866433 0.179212 -0.466022 0.668775 -0.113662 -0.734725 0.592063 -0.165143 -0.78879 0.674834 -0.0500719 -0.736269 0.860007 0.0069367 -0.510235 0.612746 0.0041994 -0.790269 0.254553 -0.0605103 -0.965164 0.535983 -0.054446 -0.842472 0.249464 -0.144612 -0.957525 0.528332 -0.103657 -0.842687 0.12185 0.029334 -0.992115 0.12185 0.029334 -0.992115 0.12185 0.029334 -0.992115 0.12185 0.029334 -0.992115 0.12185 0.029334 -0.992115 0.124053 -0.0459156 -0.991213 0.125553 -0.120905 -0.984692 0.0326569 0.0845848 -0.995881 0.0154701 0.163029 -0.9865 -0.0481555 0.657622 -0.751807 -0.0481555 0.657622 -0.751807 -0.0423706 0.62151 -0.782259 0.0278152 0.0133351 -0.999524 -0.00838985 0.300173 -0.953848 0.0651534 -0.0766469 -0.994927 0.0663879 -0.0739671 -0.995049 -0.491088 0.861183 -0.131133 -0.709033 0.685211 -0.166605 -0.672764 0.709103 -0.211096 -0.35056 0.931894 -0.0931746 -0.906623 -0.402898 -0.125334 -0.906623 -0.402898 -0.125334 -0.814465 -0.503577 -0.288198 -0.814465 -0.503577 -0.288198 -0.977074 0.0646214 -0.202857 -0.988946 0.0577864 -0.136555 -0.988946 0.0577864 -0.136555 -0.72623 0.669673 -0.155328 -0.343553 -0.938586 -0.0320598 -0.343553 -0.938586 -0.0320598 -0.318294 -0.947553 -0.0288515 -0.318294 -0.947553 -0.0288515 -0.389195 0.919735 -0.0511449 -0.389195 0.919735 -0.0511449 -0.394307 0.916151 -0.0720423 -0.394307 0.916151 -0.0720423 -0.657201 0.739803 -0.144147 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

3 1 0 3 2 1 1 2 278 1 278 277 279 277 278 279 278 141 142 141 34 142 34 32 35 32 34 33 32 31 35 31 32 281 280 32 281 32 33 37 31 35 37 36 31 39 36 37 147 37 151 60 39 37 60 37 147 39 38 36 39 60 59 147 151 150 147 150 149 147 149 148 147 148 145 145 146 147 146 145 144 146 144 143 58 143 144 58 144 157 58 57 56 58 56 55 57 58 133 157 156 58 133 58 156 134 133 3 57 133 135 3 133 155 133 156 158 158 155 133 134 3 132 7 57 134 7 134 137 132 139 138 132 138 137 137 136 132 9 7 137 9 137 140 9 8 7 57 7 8 9 4 8 54 8 53 57 8 51 5 53 8 5 8 4 54 53 49 50 49 48 52 51 49 52 49 50 50 48 47 47 48 159 161 47 159 161 159 160 163 160 159 163 159 162 284 288 163 284 163 162 284 162 290 287 285 284 284 285 288 284 290 289 284 289 287 285 46 288 287 286 285 286 302 285 285 302 46 592 286 287 592 287 591 289 591 287 289 594 591 593 592 591 593 591 472 471 472 591 471 591 594 602 286 592 356 602 592 356 592 593 602 303 286 357 611 602 357 602 356 611 303 602 357 356 353 357 353 355 354 353 352 354 352 351 286 303 302 303 317 316 303 316 302 611 317 303 302 316 45 302 45 46 42 46 45 42 45 44 43 42 41 43 41 40 468 472 471 361 358 468 468 358 470 468 470 469 468 469 472 361 360 359 361 359 358 360 363 362 360 362 359 365 364 360 324 368 363 369 368 367 324 323 368 444 367 368 444 368 445 443 368 323 369 367 366 367 466 465 367 465 455 455 452 367 466 367 444 444 467 466 444 461 467 319 462 461 461 444 319 319 463 462 319 464 463 321 320 319 321 319 318 319 444 443 319 443 442 585 320 321 585 321 584 585 584 586 585 586 451 345 451 450 343 346 345 345 450 343 344 343 342 343 344 346 343 588 587 343 587 342 344 347 346 344 348 347 348 349 347 457 347 456 347 349 371 347 371 456 348 350 349 371 349 370 456 453 454 456 454 460 456 460 459 456 459 458 456 458 457 455 454 453 455 453 452 344 342 341 344 341 480 344 480 479 344 479 478 344 478 477 477 476 344 555 341 342 555 342 587 589 550 587 555 587 550 588 582 587 590 589 587 590 587 582 589 553 550 553 551 550 555 550 551 553 552 551 555 551 554 555 554 557 555 557 556 560 556 557 555 556 341 560 559 556 556 559 558 556 558 341 558 480 341 583 334 582 588 583 582 583 333 334 334 333 332 334 332 331 576 575 334 576 334 331 331 577 576 331 578 577 331 579 578 331 580 579 331 571 580 573 581 580 573 580 571 331 572 571 571 574 567 571 567 573 331 570 572 570 569 563 570 563 568 561 564 563 562 561 563 562 563 565 567 566 563 567 563 564 561 335 564 23 336 335 335 336 431 335 431 433 23 335 561 23 24 336 25 24 23 25 23 22 120 25 22 120 22 122 253 22 23 257 22 253 121 120 119 121 119 118 253 23 252 253 252 255 253 255 254 257 253 256 256 253 254 256 259 257 256 254 258 256 260 259 256 263 262 256 262 261 259 267 264 259 264 266 265 18 264 269 268 264 269 264 18 268 266 264 268 274 266 21 19 18 265 262 18 18 19 272 18 272 271 18 271 270 270 269 18 21 20 19 19 273 272 19 20 276 19 276 275 275 276 280 275 280 281 283 275 281 241 282 281 281 33 246 281 246 241 283 281 282 244 242 241 244 241 246 241 242 282 244 243 242 244 246 245 248 245 246 30 247 246 30 246 33 248 246 247 33 31 30 167 30 31 167 249 30 249 247 30 247 251 250 247 250 248 249 251 247 31 168 167 31 171 170 31 170 169 31 169 168 173 170 171 173 171 172 172 174 173 172 28 164 172 164 176 172 176 175 172 175 174 165 164 28 28 166 165 28 29 166 29 28 27 29 27 26 26 27 69 109 69 27 109 27 28 68 67 26 68 26 66 26 69 66 109 78 69 78 109 77 77 109 110 109 28 111 78 77 76 78 76 75 75 82 81 75 81 80 80 79 73 80 73 74 85 80 74 74 73 72 299 297 73 74 72 71 84 74 71 85 74 84 71 70 67 71 67 68 84 71 83 299 298 297 301 300 297 301 297 298 601 300 301 601 301 600 601 600 599 601 599 384 385 384 383 384 391 390 384 390 383 385 383 381 381 383 395 383 390 396 383 396 395 393 386 390 393 392 386 389 387 386 389 388 387 420 387 388 380 387 420 420 388 421 380 420 340 339 340 420 339 420 422 380 340 337 380 337 377 340 339 338 340 338 337 337 379 378 337 378 377 379 382 381 379 381 378 381 395 394 473 338 339 339 474 473 339 475 474 482 475 339 482 339 481 483 482 481 481 476 484 481 484 483 476 477 485 476 485 484 255 252 561 255 561 562 23 561 252 432 431 430 432 430 429 442 449 448 442 448 447 447 446 442 443 323 448 448 323 9 448 9 140 324 9 323 324 4 9 365 324 364 324 365 322 324 322 4 6 5 4 322 6 4 3 155 154 3 154 153 153 152 3 13 11 10 13 12 11 17 15 14 117 116 14 117 14 113 131 17 14 131 14 130 17 16 15 330 16 17 330 17 329 329 428 427 329 427 426 329 17 441 329 441 440 426 425 424 426 424 423 115 114 113 115 113 112 63 62 61 61 65 64 88 87 86 90 87 88 90 89 87 94 92 91 94 93 92 96 93 94 96 95 93 100 98 97 101 100 97 100 99 98 105 103 102 105 104 103 108 107 106 126 124 123 126 125 124 436 435 126 436 126 434 129 128 127 180 178 177 177 189 188 177 188 182 180 179 178 183 179 182 183 182 181 187 185 184 187 186 185 193 191 190 197 196 190 197 190 191 193 192 191 195 191 192 198 197 191 198 191 195 195 192 194 202 200 199 207 202 199 234 207 199 234 199 233 202 201 200 204 201 202 204 202 203 202 205 203 202 206 205 207 206 202 211 209 208 216 211 208 208 209 236 208 236 235 211 210 209 213 210 211 213 211 212 211 214 212 211 215 214 216 215 211 220 218 217 220 219 218 222 218 219 222 219 221 226 224 223 226 225 224 228 225 226 228 226 227 232 230 229 232 231 230 240 238 237 240 239 238 294 292 291 291 292 296 291 296 295 294 293 292 596 293 294 596 294 595 598 596 595 598 595 597 307 305 304 304 305 309 304 309 308 307 306 305 604 306 307 604 307 603 606 604 603 606 603 605 313 311 310 315 310 311 313 312 311 608 312 313 608 313 607 315 311 314 608 607 610 608 610 609 328 326 325 328 327 326 374 373 372 376 372 375 399 398 397 399 401 400 399 400 398 405 403 402 405 404 403 404 406 403 404 407 406 411 409 408 409 412 408 411 410 409 416 414 413 416 415 414 419 418 417 439 438 437 489 487 486 498 497 486 498 486 492 489 488 487 492 488 491 492 491 490 496 494 493 496 495 494 502 500 499 499 506 505 499 505 502 502 501 500 501 502 504 502 505 507 502 507 504 501 504 503 511 509 508 509 516 508 508 516 543 508 543 542 511 510 509 509 510 513 509 513 512 515 509 512 515 514 509 509 514 516 520 518 517 518 525 517 545 520 517 545 517 544 520 519 518 518 519 522 518 522 521 524 518 521 524 523 518 518 523 525 529 527 526 529 528 527 528 529 531 528 531 530 535 533 532 535 534 533 533 534 537 533 537 536 541 539 538 541 540 539 549 547 546 549 548 547

+
+
+
+ + + + 1.33372 0.517748 0.848829 1.3847 0.511035 0.848829 1.43221 0.491355 0.848829 1.47301 0.460049 0.848829 1.50432 0.419249 0.848829 1.524 0.371738 0.848829 1.53071 0.320751 0.848829 1.524 0.269765 0.848829 1.50432 0.222253 0.848829 1.47301 0.181453 0.848829 1.43221 0.150147 0.848829 1.3847 0.130467 0.848829 1.33372 0.123754 0.848829 1.28273 0.130467 0.848829 1.23522 0.150147 0.848829 1.19442 0.181453 0.848829 1.16311 0.222253 0.848829 1.14343 0.269765 0.848829 1.13672 0.320751 0.848829 1.14343 0.371738 0.848829 1.16311 0.419249 0.848829 1.19442 0.460049 0.848829 1.23522 0.491355 0.848829 1.28273 0.511035 0.848829 1.33372 0.517748 -0.848829 1.28273 0.511035 -0.848829 1.23522 0.491355 -0.848829 1.19442 0.460049 -0.848829 1.16311 0.419249 -0.848829 1.14343 0.371738 -0.848829 1.13672 0.320751 -0.848829 1.14343 0.269765 -0.848829 1.16311 0.222253 -0.848829 1.19442 0.181453 -0.848829 1.23522 0.150147 -0.848829 1.28273 0.130467 -0.848829 1.33372 0.123754 -0.848829 1.3847 0.130467 -0.848829 1.43221 0.150147 -0.848829 1.47301 0.181453 -0.848829 1.50432 0.222253 -0.848829 1.524 0.269765 -0.848829 1.53071 0.320751 -0.848829 1.524 0.371738 -0.848829 1.50432 0.419249 -0.848829 1.47301 0.460049 -0.848829 1.43221 0.491355 -0.848829 1.3847 0.511035 -0.848829 -1.28831 0.517748 -0.848829 -1.3393 0.511035 -0.848829 -1.38681 0.491355 -0.848829 -1.42761 0.460049 -0.848829 -1.45892 0.419249 -0.848829 -1.4786 0.371738 -0.848829 -1.48531 0.320751 -0.848829 -1.4786 0.269765 -0.848829 -1.45892 0.222253 -0.848829 -1.42761 0.181453 -0.848829 -1.38681 0.150147 -0.848829 -1.3393 0.130467 -0.848829 -1.28831 0.123754 -0.848829 -1.23733 0.130467 -0.848829 -1.18982 0.150147 -0.848829 -1.14902 0.181453 -0.848829 -1.11771 0.222253 -0.848829 -1.09803 0.269765 -0.848829 -1.09132 0.320751 -0.848829 -1.09803 0.371738 -0.848829 -1.11771 0.419249 -0.848829 -1.14902 0.460049 -0.848829 -1.18982 0.491355 -0.848829 -1.23733 0.511035 -0.848829 -1.28831 0.517748 0.848829 -1.23733 0.511035 0.848829 -1.18982 0.491355 0.848829 -1.14902 0.460049 0.848829 -1.11771 0.419249 0.848829 -1.09803 0.371738 0.848829 -1.09132 0.320751 0.848829 -1.09803 0.269765 0.848829 -1.11771 0.222253 0.848829 -1.14902 0.181453 0.848829 -1.18982 0.150147 0.848829 -1.23733 0.130467 0.848829 -1.28831 0.123754 0.848829 -1.3393 0.130467 0.848829 -1.38681 0.150147 0.848829 -1.42761 0.181453 0.848829 -1.45892 0.222253 0.848829 -1.4786 0.269765 0.848829 -1.48531 0.320751 0.848829 -1.4786 0.371738 0.848829 -1.45892 0.419249 0.848829 -1.42761 0.460049 0.848829 -1.38681 0.491355 0.848829 -1.3393 0.511035 0.848829 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 23 22 0 22 21 0 21 20 0 20 19 0 19 18 0 18 17 0 17 16 0 16 15 0 15 14 0 14 13 0 13 12 0 12 11 0 11 10 0 10 9 0 9 8 0 8 7 0 7 6 0 6 5 0 5 4 0 4 3 0 3 2 2 1 0 24 47 46 24 46 45 24 45 44 24 44 43 24 43 42 24 42 41 24 41 40 24 40 39 24 39 38 24 38 37 24 37 36 24 36 35 24 35 34 24 34 33 24 33 32 24 32 31 24 31 30 24 30 29 24 29 28 24 28 27 24 27 26 26 25 24 48 71 70 48 70 69 48 69 68 48 68 67 48 67 66 48 66 65 48 65 64 48 64 63 48 63 62 48 62 61 48 61 60 48 60 59 48 59 58 48 58 57 48 57 56 48 56 55 48 55 54 48 54 53 48 53 52 48 52 51 48 51 50 50 49 48 72 95 94 72 94 93 72 93 92 72 92 91 72 91 90 72 90 89 72 89 88 72 88 87 72 87 86 72 86 85 72 85 84 72 84 83 72 83 82 72 82 81 72 81 80 72 80 79 72 79 78 72 78 77 72 77 76 72 76 75 72 75 74 74 73 72

+
+
+
+ + + + -1.92228 0.666133 0.61557 -2.0405 0.652288 0.44943 -1.97234 0.735358 0.476055 -1.86797 0.782218 0.617167 -1.86158 0.801388 0.50268 -1.77105 0.847183 0.593205 -1.69837 0.823497 0.672195 -1.79555 0.705538 0.75402 -1.48244 0.854638 0.76254 -1.65497 0.858898 0.67521 -1.934 0.300412 0.74124 -2.0021 0.298708 0.648585 -1.99728 0.419053 0.648585 -1.91584 0.41458 0.7455 -1.98181 0.526618 0.648585 -1.90833 0.522358 0.74337 1.88722 1.11876 0.64326 1.88935 1.02397 0.71994 1.73173 1.02078 0.7455 1.9213 1.13047 0.61344 1.9426 1.12941 0.56232 1.91917 0.980308 0.56232 1.94253 0.760196 0.738503 1.95038 0.721298 0.74124 1.93189 0.727388 0.77615 2.00849 0.751337 0.564131 -1.92228 0.666133 -0.61557 -1.86797 0.782218 -0.617167 -1.97234 0.735358 -0.476055 -2.0405 0.652288 -0.44943 -1.77105 0.847183 -0.593205 -1.86158 0.801388 -0.50268 -1.79555 0.705538 -0.75402 -1.69837 0.823497 -0.672195 -1.48244 0.854638 -0.76254 -1.65497 0.858898 -0.67521 -1.934 0.300412 -0.74124 -1.91584 0.41458 -0.7455 -1.99728 0.419053 -0.648585 -2.0021 0.298708 -0.648585 -1.90833 0.522358 -0.74337 -1.98181 0.526618 -0.648585 1.88722 1.11876 -0.64326 1.73173 1.02078 -0.7455 1.88935 1.02397 -0.71994 1.9213 1.13047 -0.61344 1.91917 0.980308 -0.56232 1.9426 1.12941 -0.56232 1.93189 0.727388 -0.77615 1.95038 0.721298 -0.74124 1.94253 0.760196 -0.738503 2.00849 0.751337 -0.564131 + + + + + + + + + + -0.586528 0.263895 0.765732 -0.775287 0.355568 0.522016 -0.695038 0.634077 0.338922 -0.55911 0.580577 0.591884 -0.5331 0.838063 0.115994 -0.461489 0.816453 0.347034 -0.371649 0.564827 0.736782 -0.366633 0.453741 0.812219 -0.355772 0.712566 0.604711 -0.362662 0.746693 0.557607 -0.802158 0.105654 0.58769 -0.802158 0.105654 0.58769 -0.782897 0.0858109 0.616205 -0.782897 0.0858109 0.616205 -0.7624 0.0658325 0.643749 -0.7624 0.0658325 0.643749 0.267552 0.609644 0.746157 0.573452 0.392395 0.719151 0.136249 0.427583 0.893649 0.721727 0.36906 0.585581 0.918751 0.104994 0.380621 0.919929 0.15715 0.359214 0.616494 0.238309 0.750429 0.152615 0.205115 0.966766 0.152615 0.205115 0.966766 0.918181 0.208807 0.336665 -0.586528 0.263895 -0.765732 -0.55911 0.580577 -0.591884 -0.695038 0.634077 -0.338922 -0.775287 0.355568 -0.522016 -0.461489 0.816453 -0.347034 -0.5331 0.838063 -0.115994 -0.366633 0.453741 -0.812219 -0.371649 0.564827 -0.736782 -0.355772 0.712566 -0.604711 -0.362662 0.746693 -0.557607 -0.802158 0.105654 -0.58769 -0.782897 0.0858109 -0.616205 -0.782897 0.0858109 -0.616205 -0.802158 0.105654 -0.58769 -0.7624 0.0658325 -0.643749 -0.7624 0.0658325 -0.643749 0.267552 0.609644 -0.746157 0.136249 0.427583 -0.893649 0.573452 0.392395 -0.719152 0.721727 0.36906 -0.585581 0.919929 0.15715 -0.359214 0.918751 0.104994 -0.380621 0.152615 0.205115 -0.966766 0.152615 0.205115 -0.966766 0.616494 0.238309 -0.750429 0.918181 0.208807 -0.336665 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

3 1 0 0 7 6 0 6 3 3 2 1 5 2 3 6 5 3 7 8 6 6 9 5 5 4 2 13 11 10 13 12 11 15 12 13 15 14 12 18 17 16 17 19 16 18 24 23 18 23 22 22 17 18 25 17 22 25 21 17 17 21 20 17 20 19 29 27 26 33 32 26 33 26 27 29 28 27 28 30 27 30 33 27 34 32 33 30 35 33 28 31 30 39 37 36 39 38 37 38 40 37 38 41 40 44 43 42 45 44 42 43 44 50 43 50 49 49 48 43 44 51 50 44 46 51 47 46 44 47 44 45

+
+
+
+ + + + 2.02424 0.710947 0.56445 1.95038 0.721298 0.74124 1.94253 0.760196 0.738503 2.00849 0.751337 0.564131 2.02424 0.710947 -0.56445 2.00849 0.751337 -0.564131 1.94253 0.760196 -0.738503 1.95038 0.721298 -0.74124 + + + + + + + + + + 0.873558 0.343462 0.344863 0.873558 0.343462 0.344863 0.873558 0.343462 0.344863 0.873558 0.343462 0.344863 0.873558 0.343462 -0.344863 0.873558 0.343462 -0.344863 0.873558 0.343462 -0.344863 0.873558 0.343462 -0.344863 + + + + + + + + + + + + + + + 3 3 3 3 +

3 2 1 3 1 0 7 6 5 7 5 4

+
+
+
+ + + + 2.10153 1.1482 -0 2.0679 1.13937 0.519197 2.05338 1.16683 0.517603 2.08741 1.17814 -0 1.9426 1.12941 0.56232 2.0679 1.13937 0.519197 2.10153 1.1482 -0 1.96816 1.14006 -0 1.9426 1.12941 0.56232 1.83114 1.18694 0.556371 1.86828 1.20094 -0 1.2509 1.26793 0.634564 1.40371 1.21674 0.644733 1.40371 1.18692 0.660416 1.29273 1.07593 0.730956 1.26633 1.07403 0.73485 -0.326705 1.30968 0.595948 0.0732339 1.38393 0.58526 0.073831 1.35406 0.598098 -0.327476 1.27442 0.612271 -0.69767 0.927629 0.76394 -1.12663 0.89058 0.770622 -1.13951 0.927058 0.740882 -0.871126 1.08042 0.677811 -0.589966 1.21248 0.629745 -0.670906 1.1358 0.667356 0.316411 1.00818 0.747084 0.158954 1.00015 0.750299 0.227954 1.36158 0.595693 0.436694 1.39566 0.582858 0.760556 1.37986 0.59096 0.761847 1.35222 0.602606 0.342974 1.3701 0.592918 0.984991 1.04967 0.73648 0.990494 1.2423 0.655645 0.939374 1.32324 0.61634 0.986234 1.34454 0.605104 -0.71447 0.852416 0.792656 -0.712856 0.890743 0.844192 -0.728894 0.91108 0.813996 -0.721058 0.888935 0.773473 -0.766319 0.883735 0.77568 -0.758395 0.911579 0.834925 -0.75736 0.845694 0.794984 -0.766319 0.883735 0.77568 -0.758395 0.911579 0.834925 -0.740324 0.89203 0.870733 -0.71447 0.852416 0.792656 -0.712856 0.890743 0.844192 2.05338 1.16683 -0.517603 2.0679 1.13937 -0.519197 1.9426 1.12941 -0.56232 2.0679 1.13937 -0.519197 1.9426 1.12941 -0.56232 1.83114 1.18694 -0.556371 1.2509 1.26793 -0.634564 1.26633 1.07403 -0.73485 1.29273 1.07593 -0.730956 1.40371 1.18692 -0.660416 1.40371 1.21674 -0.644733 -0.326705 1.30968 -0.595948 -0.327476 1.27442 -0.612271 0.073831 1.35406 -0.598098 0.0732339 1.38393 -0.58526 -0.69767 0.927629 -0.76394 -0.670906 1.1358 -0.667356 -0.589966 1.21248 -0.629745 -0.871126 1.08042 -0.677811 -1.13951 0.927058 -0.740882 -1.12663 0.89058 -0.770622 0.316411 1.00818 -0.747084 0.342974 1.3701 -0.592918 0.761847 1.35222 -0.602606 0.760556 1.37986 -0.59096 0.436694 1.39566 -0.582858 0.227954 1.36158 -0.595693 0.158954 1.00015 -0.750299 0.986234 1.34454 -0.605104 0.939374 1.32324 -0.61634 0.990494 1.2423 -0.655645 0.984991 1.04967 -0.73648 -0.71447 0.852416 -0.792656 -0.721058 0.888935 -0.773473 -0.728894 0.91108 -0.813996 -0.712856 0.890743 -0.844192 -0.766319 0.883735 -0.77568 -0.758395 0.911579 -0.834925 -0.75736 0.845694 -0.794984 -0.740324 0.89203 -0.870733 -0.758395 0.911579 -0.834925 -0.766319 0.883735 -0.77568 -0.71447 0.852416 -0.792656 -0.712856 0.890743 -0.844192 1.41585 0.613656 0.828183 1.33717 0.624015 0.828183 1.33768 0.640016 0.735278 1.42051 0.629112 0.735278 1.48917 0.583286 0.828183 1.49769 0.597143 0.735278 1.55213 0.534974 0.828183 1.56396 0.546287 0.735278 1.60045 0.472012 0.828183 1.61482 0.480012 0.735278 1.63082 0.398691 0.828183 1.64679 0.402832 0.735278 1.64117 0.320008 0.828183 1.65769 0.320008 0.735278 1.63082 0.241325 0.828183 1.64679 0.237184 0.735278 1.60045 0.168004 0.828183 1.61482 0.160004 0.735278 1.55213 0.105042 0.828183 1.56396 0.0937282 0.735278 1.18516 0.0567298 0.828183 1.17768 0.042873 0.735278 1.1114 0.0937282 0.735278 1.1222 0.105042 0.828183 1.06055 0.160004 0.735278 1.07389 0.168004 0.828183 1.02858 0.237184 0.735278 1.04352 0.241325 0.828183 1.01768 0.320008 0.735278 1.03316 0.320008 0.828183 1.02858 0.402832 0.735278 1.04352 0.398691 0.828183 1.06055 0.480012 0.735278 1.07389 0.472012 0.828183 1.1114 0.546287 0.735278 1.1222 0.534974 0.828183 1.17768 0.597143 0.735278 1.18516 0.583286 0.828183 1.25486 0.629112 0.735278 1.25849 0.613656 0.828183 1.33737 0.630415 0.632049 1.25704 0.619838 0.632049 1.18217 0.588829 0.632049 1.11788 0.539499 0.632049 1.06855 0.475212 0.632049 1.03754 0.400347 0.632049 1.02697 0.320008 0.632049 1.03754 0.239669 0.632049 1.06855 0.164804 0.632049 1.11788 0.100517 0.632049 1.18217 0.0511869 0.632049 1.25704 0.0201772 0.632049 1.33737 0.00960024 0.632049 1.41771 0.0201772 0.632049 1.49258 0.0511869 0.632049 1.55687 0.100517 0.632049 1.60619 0.164804 0.632049 1.63721 0.239669 0.632049 1.64778 0.320008 0.632049 1.63721 0.400347 0.632049 1.60619 0.475212 0.632049 1.55687 0.539499 0.632049 1.49258 0.588829 0.632049 1.41771 0.619838 0.632049 1.33619 0.594647 0.859151 1.26537 0.585324 0.859151 1.407 0.585324 0.859151 1.47299 0.55799 0.859151 1.52966 0.514509 0.859151 1.57314 0.457843 0.859151 1.60047 0.391855 0.859151 1.60979 0.32104 0.859151 1.60047 0.250226 0.859151 1.57314 0.184237 0.859151 1.52966 0.127571 0.859151 1.14272 0.127571 0.859151 1.19938 0.0840898 0.859151 1.09924 0.184237 0.859151 1.0719 0.250226 0.859151 1.06258 0.32104 0.859151 1.0719 0.391855 0.859151 1.09924 0.457843 0.859151 1.14272 0.514509 0.859151 1.19938 0.55799 0.859151 1.33372 0.517748 0.848829 1.28273 0.511035 0.848829 1.3847 0.511035 0.848829 1.43221 0.491355 0.848829 1.47301 0.460049 0.848829 1.50432 0.419249 0.848829 1.524 0.371738 0.848829 1.53071 0.320751 0.848829 1.524 0.269765 0.848829 1.50432 0.222253 0.848829 1.47301 0.181453 0.848829 1.19442 0.181453 0.848829 1.23522 0.150147 0.848829 1.16311 0.222253 0.848829 1.14343 0.269765 0.848829 1.13672 0.320751 0.848829 1.14343 0.371738 0.848829 1.16311 0.419249 0.848829 1.19442 0.460049 0.848829 1.23522 0.491355 0.848829 1.48917 0.0567298 0.828183 1.49769 0.042873 0.735278 1.41585 0.0263593 0.828183 1.42051 0.010904 0.735278 1.33717 0.0160004 0.828183 1.33768 0 0.735278 1.25486 0.010904 0.735278 1.25849 0.0263593 0.828183 1.47299 0.0840898 0.859151 1.407 0.0567564 0.859151 1.33619 0.0474334 0.859151 1.26537 0.0567564 0.859151 1.43221 0.150147 0.848829 1.3847 0.130467 0.848829 1.33372 0.123754 0.848829 1.28273 0.130467 0.848829 -1.20618 0.613656 0.828183 -1.28486 0.624015 0.828183 -1.28435 0.640016 0.735278 -1.20152 0.629112 0.735278 -1.13286 0.583286 0.828183 -1.12434 0.597143 0.735278 -1.0699 0.534974 0.828183 -1.05807 0.546287 0.735278 -1.02158 0.472012 0.828183 -1.00721 0.480012 0.735278 -0.991213 0.398691 0.828183 -0.975242 0.402832 0.735278 -0.980855 0.320008 0.828183 -0.964338 0.320008 0.735278 -0.991213 0.241325 0.828183 -0.975242 0.237184 0.735278 -1.02158 0.168004 0.828183 -1.00721 0.160004 0.735278 -1.0699 0.105042 0.828183 -1.05807 0.0937282 0.735278 -1.43687 0.0567298 0.828183 -1.44435 0.042873 0.735278 -1.51063 0.0937282 0.735278 -1.49983 0.105042 0.828183 -1.56148 0.160004 0.735278 -1.54814 0.168004 0.828183 -1.59345 0.237184 0.735278 -1.57851 0.241325 0.828183 -1.60435 0.320008 0.735278 -1.58887 0.320008 0.828183 -1.59345 0.402832 0.735278 -1.57851 0.398691 0.828183 -1.56148 0.480012 0.735278 -1.54814 0.472012 0.828183 -1.51063 0.546287 0.735278 -1.49983 0.534974 0.828183 -1.44435 0.597143 0.735278 -1.43687 0.583286 0.828183 -1.36717 0.629112 0.735278 -1.36354 0.613656 0.828183 -1.28466 0.630415 0.632049 -1.36499 0.619838 0.632049 -1.43986 0.588829 0.632049 -1.50415 0.539499 0.632049 -1.55348 0.475212 0.632049 -1.58449 0.400347 0.632049 -1.59506 0.320008 0.632049 -1.58449 0.239669 0.632049 -1.55348 0.164804 0.632049 -1.50415 0.100517 0.632049 -1.43986 0.0511869 0.632049 -1.36499 0.0201772 0.632049 -1.28466 0.00960024 0.632049 -1.20432 0.0201772 0.632049 -1.12945 0.0511869 0.632049 -1.06516 0.100517 0.632049 -1.01584 0.164804 0.632049 -0.984825 0.239669 0.632049 -0.974248 0.320008 0.632049 -0.984825 0.400347 0.632049 -1.01584 0.475212 0.632049 -1.06516 0.539499 0.632049 -1.12945 0.588829 0.632049 -1.20432 0.619838 0.632049 -1.28584 0.594647 0.859151 -1.35666 0.585324 0.859151 -1.21503 0.585324 0.859151 -1.14904 0.55799 0.859151 -1.09237 0.514509 0.859151 -1.04889 0.457843 0.859151 -1.02156 0.391855 0.859151 -1.01224 0.32104 0.859151 -1.02156 0.250226 0.859151 -1.04889 0.184237 0.859151 -1.09237 0.127571 0.859151 -1.47931 0.127571 0.859151 -1.42265 0.0840898 0.859151 -1.52279 0.184237 0.859151 -1.55013 0.250226 0.859151 -1.55945 0.32104 0.859151 -1.55013 0.391855 0.859151 -1.52279 0.457843 0.859151 -1.47931 0.514509 0.859151 -1.42265 0.55799 0.859151 -1.28831 0.517748 0.848829 -1.3393 0.511035 0.848829 -1.23733 0.511035 0.848829 -1.18982 0.491355 0.848829 -1.14902 0.460049 0.848829 -1.11771 0.419249 0.848829 -1.09803 0.371738 0.848829 -1.09132 0.320751 0.848829 -1.09803 0.269765 0.848829 -1.11771 0.222253 0.848829 -1.14902 0.181453 0.848829 -1.42761 0.181453 0.848829 -1.38681 0.150147 0.848829 -1.45892 0.222253 0.848829 -1.4786 0.269765 0.848829 -1.48531 0.320751 0.848829 -1.4786 0.371738 0.848829 -1.45892 0.419249 0.848829 -1.42761 0.460049 0.848829 -1.38681 0.491355 0.848829 -1.13286 0.0567298 0.828183 -1.12434 0.042873 0.735278 -1.20618 0.0263593 0.828183 -1.20152 0.010904 0.735278 -1.28486 0.0160004 0.828183 -1.28435 0 0.735278 -1.36717 0.010904 0.735278 -1.36354 0.0263593 0.828183 -1.14904 0.0840898 0.859151 -1.21503 0.0567564 0.859151 -1.28584 0.0474334 0.859151 -1.35666 0.0567564 0.859151 -1.18982 0.150147 0.848829 -1.23733 0.130467 0.848829 -1.28831 0.123754 0.848829 -1.3393 0.130467 0.848829 1.41585 0.613656 -0.828183 1.42051 0.629112 -0.735278 1.33768 0.640016 -0.735278 1.33717 0.624015 -0.828183 1.48917 0.583286 -0.828183 1.49769 0.597143 -0.735278 1.55213 0.534974 -0.828183 1.56396 0.546287 -0.735278 1.60045 0.472012 -0.828183 1.61482 0.480012 -0.735278 1.63082 0.398691 -0.828183 1.64679 0.402832 -0.735278 1.64117 0.320008 -0.828183 1.65769 0.320008 -0.735278 1.63082 0.241325 -0.828183 1.64679 0.237184 -0.735278 1.60045 0.168004 -0.828183 1.61482 0.160004 -0.735278 1.55213 0.105042 -0.828183 1.56396 0.0937282 -0.735278 1.18516 0.0567298 -0.828183 1.1222 0.105042 -0.828183 1.1114 0.0937282 -0.735278 1.17768 0.042873 -0.735278 1.07389 0.168004 -0.828183 1.06055 0.160004 -0.735278 1.04352 0.241325 -0.828183 1.02858 0.237184 -0.735278 1.03316 0.320008 -0.828183 1.01768 0.320008 -0.735278 1.04352 0.398691 -0.828183 1.02858 0.402832 -0.735278 1.07389 0.472012 -0.828183 1.06055 0.480012 -0.735278 1.1222 0.534974 -0.828183 1.1114 0.546287 -0.735278 1.18516 0.583286 -0.828183 1.17768 0.597143 -0.735278 1.25849 0.613656 -0.828183 1.25486 0.629112 -0.735278 1.33737 0.630415 -0.632049 1.41771 0.619838 -0.632049 1.49258 0.588829 -0.632049 1.55687 0.539499 -0.632049 1.60619 0.475212 -0.632049 1.63721 0.400347 -0.632049 1.64778 0.320008 -0.632049 1.63721 0.239669 -0.632049 1.60619 0.164804 -0.632049 1.55687 0.100517 -0.632049 1.49258 0.0511869 -0.632049 1.41771 0.0201772 -0.632049 1.33737 0.00960024 -0.632049 1.25704 0.0201772 -0.632049 1.18217 0.0511869 -0.632049 1.11788 0.100517 -0.632049 1.06855 0.164804 -0.632049 1.03754 0.239669 -0.632049 1.02697 0.320008 -0.632049 1.03754 0.400347 -0.632049 1.06855 0.475212 -0.632049 1.11788 0.539499 -0.632049 1.18217 0.588829 -0.632049 1.25704 0.619838 -0.632049 1.26537 0.585324 -0.859151 1.33619 0.594647 -0.859151 1.407 0.585324 -0.859151 1.47299 0.55799 -0.859151 1.52966 0.514509 -0.859151 1.57314 0.457843 -0.859151 1.60047 0.391855 -0.859151 1.60979 0.32104 -0.859151 1.60047 0.250226 -0.859151 1.57314 0.184237 -0.859151 1.52966 0.127571 -0.859151 1.19938 0.0840898 -0.859151 1.14272 0.127571 -0.859151 1.09924 0.184237 -0.859151 1.0719 0.250226 -0.859151 1.06258 0.32104 -0.859151 1.0719 0.391855 -0.859151 1.09924 0.457843 -0.859151 1.14272 0.514509 -0.859151 1.19938 0.55799 -0.859151 1.28273 0.511035 -0.848829 1.33372 0.517748 -0.848829 1.3847 0.511035 -0.848829 1.43221 0.491355 -0.848829 1.47301 0.460049 -0.848829 1.50432 0.419249 -0.848829 1.524 0.371738 -0.848829 1.53071 0.320751 -0.848829 1.524 0.269765 -0.848829 1.50432 0.222253 -0.848829 1.47301 0.181453 -0.848829 1.23522 0.150147 -0.848829 1.19442 0.181453 -0.848829 1.16311 0.222253 -0.848829 1.14343 0.269765 -0.848829 1.13672 0.320751 -0.848829 1.14343 0.371738 -0.848829 1.16311 0.419249 -0.848829 1.19442 0.460049 -0.848829 1.23522 0.491355 -0.848829 1.48917 0.0567298 -0.828183 1.49769 0.042873 -0.735278 1.41585 0.0263593 -0.828183 1.42051 0.010904 -0.735278 1.33717 0.0160004 -0.828183 1.33768 0 -0.735278 1.25849 0.0263593 -0.828183 1.25486 0.010904 -0.735278 1.47299 0.0840898 -0.859151 1.407 0.0567564 -0.859151 1.33619 0.0474334 -0.859151 1.26537 0.0567564 -0.859151 1.43221 0.150147 -0.848829 1.3847 0.130467 -0.848829 1.33372 0.123754 -0.848829 1.28273 0.130467 -0.848829 -1.20618 0.613656 -0.828183 -1.20152 0.629112 -0.735278 -1.28435 0.640016 -0.735278 -1.28486 0.624015 -0.828183 -1.13286 0.583286 -0.828183 -1.12434 0.597143 -0.735278 -1.0699 0.534974 -0.828183 -1.05807 0.546287 -0.735278 -1.02158 0.472012 -0.828183 -1.00721 0.480012 -0.735278 -0.991213 0.398691 -0.828183 -0.975242 0.402832 -0.735278 -0.980855 0.320008 -0.828183 -0.964338 0.320008 -0.735278 -0.991213 0.241325 -0.828183 -0.975242 0.237184 -0.735278 -1.02158 0.168004 -0.828183 -1.00721 0.160004 -0.735278 -1.0699 0.105042 -0.828183 -1.05807 0.0937282 -0.735278 -1.43687 0.0567298 -0.828183 -1.49983 0.105042 -0.828183 -1.51063 0.0937282 -0.735278 -1.44435 0.042873 -0.735278 -1.54814 0.168004 -0.828183 -1.56148 0.160004 -0.735278 -1.57851 0.241325 -0.828183 -1.59345 0.237184 -0.735278 -1.58887 0.320008 -0.828183 -1.60435 0.320008 -0.735278 -1.57851 0.398691 -0.828183 -1.59345 0.402832 -0.735278 -1.54814 0.472012 -0.828183 -1.56148 0.480012 -0.735278 -1.49983 0.534974 -0.828183 -1.51063 0.546287 -0.735278 -1.43687 0.583286 -0.828183 -1.44435 0.597143 -0.735278 -1.36354 0.613656 -0.828183 -1.36717 0.629112 -0.735278 -1.28466 0.630415 -0.632049 -1.20432 0.619838 -0.632049 -1.12945 0.588829 -0.632049 -1.06516 0.539499 -0.632049 -1.01584 0.475212 -0.632049 -0.984825 0.400347 -0.632049 -0.974248 0.320008 -0.632049 -0.984825 0.239669 -0.632049 -1.01584 0.164804 -0.632049 -1.06516 0.100517 -0.632049 -1.12945 0.0511869 -0.632049 -1.20432 0.0201772 -0.632049 -1.28466 0.00960024 -0.632049 -1.36499 0.0201772 -0.632049 -1.43986 0.0511869 -0.632049 -1.50415 0.100517 -0.632049 -1.55348 0.164804 -0.632049 -1.58449 0.239669 -0.632049 -1.59506 0.320008 -0.632049 -1.58449 0.400347 -0.632049 -1.55348 0.475212 -0.632049 -1.50415 0.539499 -0.632049 -1.43986 0.588829 -0.632049 -1.36499 0.619838 -0.632049 -1.35666 0.585324 -0.859151 -1.28584 0.594647 -0.859151 -1.21503 0.585324 -0.859151 -1.14904 0.55799 -0.859151 -1.09237 0.514509 -0.859151 -1.04889 0.457843 -0.859151 -1.02156 0.391855 -0.859151 -1.01224 0.32104 -0.859151 -1.02156 0.250226 -0.859151 -1.04889 0.184237 -0.859151 -1.09237 0.127571 -0.859151 -1.42265 0.0840898 -0.859151 -1.47931 0.127571 -0.859151 -1.52279 0.184237 -0.859151 -1.55013 0.250226 -0.859151 -1.55945 0.32104 -0.859151 -1.55013 0.391855 -0.859151 -1.52279 0.457843 -0.859151 -1.47931 0.514509 -0.859151 -1.42265 0.55799 -0.859151 -1.3393 0.511035 -0.848829 -1.28831 0.517748 -0.848829 -1.23733 0.511035 -0.848829 -1.18982 0.491355 -0.848829 -1.14902 0.460049 -0.848829 -1.11771 0.419249 -0.848829 -1.09803 0.371738 -0.848829 -1.09132 0.320751 -0.848829 -1.09803 0.269765 -0.848829 -1.11771 0.222253 -0.848829 -1.14902 0.181453 -0.848829 -1.38681 0.150147 -0.848829 -1.42761 0.181453 -0.848829 -1.45892 0.222253 -0.848829 -1.4786 0.269765 -0.848829 -1.48531 0.320751 -0.848829 -1.4786 0.371738 -0.848829 -1.45892 0.419249 -0.848829 -1.42761 0.460049 -0.848829 -1.38681 0.491355 -0.848829 -1.13286 0.0567298 -0.828183 -1.12434 0.042873 -0.735278 -1.20618 0.0263593 -0.828183 -1.20152 0.010904 -0.735278 -1.28486 0.0160004 -0.828183 -1.28435 0 -0.735278 -1.36354 0.0263593 -0.828183 -1.36717 0.010904 -0.735278 -1.14904 0.0840898 -0.859151 -1.21503 0.0567564 -0.859151 -1.28584 0.0474334 -0.859151 -1.35666 0.0567564 -0.859151 -1.18982 0.150147 -0.848829 -1.23733 0.130467 -0.848829 -1.28831 0.123754 -0.848829 -1.3393 0.130467 -0.848829 + + + + + + + + + + 0.904413 0.426657 -0 0.657963 0.558188 0.505481 0.495977 0.788289 0.364153 0.57482 0.81828 -0 0.073945 -0.997141 -0.0155242 0.073945 -0.997141 -0.0155242 0.073954 -0.997262 -0 0.073954 -0.997262 -0 0.235337 0.539523 0.808413 0.185848 0.861929 0.471739 0.095568 0.995423 -0 0.0311485 0.461135 0.886783 0.0965697 0.46331 0.880919 0.0965697 0.46331 0.880919 0.0965697 0.46331 0.880919 0.0311485 0.461135 0.886783 -0.0381509 0.421848 0.905864 -0.0275451 0.406401 0.913279 -0.0275451 0.406401 0.913279 -0.0381509 0.421848 0.905864 -0.0224361 0.423142 0.905785 -0.0224361 0.423142 0.905785 -0.0224361 0.423142 0.905785 -0.0224361 0.423142 0.905785 -0.0224361 0.423142 0.905785 -0.0224361 0.423142 0.905785 -0.00120804 0.39197 0.919977 -0.00120804 0.39197 0.919977 -0.00120804 0.39197 0.919977 -0.00120804 0.39197 0.919977 -0.0178217 0.424804 0.90511 -0.0178217 0.424804 0.90511 -0.00120804 0.39197 0.919977 -0.0344073 0.456969 0.888817 -0.0344073 0.456969 0.888817 -0.0344073 0.456969 0.888817 -0.0344073 0.456969 0.888817 0.986259 0.116273 -0.117366 0.986259 0.116273 -0.117366 0.600612 0.710754 -0.366188 0.600612 0.710754 -0.366188 -0.123806 0.904339 -0.408465 -0.123806 0.904339 -0.408465 -0.546227 -0.601579 0.582871 -0.958773 -0.0888012 0.269943 -0.958773 -0.0888012 0.269943 -0.546227 -0.601579 0.582871 0.156397 -0.794884 0.586259 0.156397 -0.794884 0.586259 0.495977 0.788289 -0.364153 0.657963 0.558188 -0.505481 0.073945 -0.997141 0.0155242 0.073945 -0.997141 0.0155242 0.235337 0.539523 -0.808413 0.185848 0.861929 -0.471739 0.0311485 0.461135 -0.886783 0.0311485 0.461135 -0.886783 0.0965697 0.46331 -0.880919 0.0965697 0.46331 -0.880919 0.0965697 0.46331 -0.880919 -0.0381509 0.421848 -0.905864 -0.0381509 0.421848 -0.905864 -0.0275451 0.406401 -0.913279 -0.0275451 0.406401 -0.913279 -0.0224361 0.423142 -0.905785 -0.0224361 0.423142 -0.905785 -0.0224361 0.423142 -0.905785 -0.0224361 0.423142 -0.905785 -0.0224361 0.423142 -0.905785 -0.0224361 0.423142 -0.905785 -0.00120804 0.39197 -0.919977 -0.00120804 0.39197 -0.919977 -0.0178217 0.424804 -0.90511 -0.0178217 0.424804 -0.90511 -0.00120804 0.39197 -0.919977 -0.00120804 0.39197 -0.919977 -0.00120804 0.39197 -0.919977 -0.0344073 0.456969 -0.888817 -0.0344073 0.456969 -0.888817 -0.0344073 0.456969 -0.888817 -0.0344073 0.456969 -0.888817 0.986259 0.116273 0.117366 0.600612 0.710754 0.366188 0.600612 0.710754 0.366188 0.986259 0.116273 0.117366 -0.123806 0.904339 0.408465 -0.123806 0.904339 0.408465 -0.546227 -0.601579 -0.582871 -0.546227 -0.601579 -0.582871 -0.958773 -0.0888012 -0.269943 -0.958773 -0.0888012 -0.269943 0.156397 -0.794884 -0.586259 0.156397 -0.794884 -0.586259 0.230807 0.861902 0.4515 -0.000111246 0.89369 0.448685 -1.02282e-05 0.999243 0.0389102 0.25861 0.965185 0.0392236 0.445212 0.771428 0.454627 0.499601 0.865354 0.0395156 0.628532 0.628753 0.45784 0.706543 0.706552 0.0397639 0.768473 0.443849 0.460919 0.865331 0.499605 0.0399555 0.855793 0.229438 0.463655 0.965149 0.258613 0.0400796 0.884849 0.000106329 0.465878 0.999195 -1.21335e-07 0.0401205 0.853917 -0.228725 0.467451 0.965149 -0.258613 0.0400757 0.765224 -0.44176 0.468273 0.865331 -0.499605 0.0399555 0.624774 -0.624781 0.468301 0.706543 -0.706552 0.0397663 -0.444563 -0.769706 0.458166 -0.499641 -0.865385 0.0383048 -0.7066 -0.706589 0.0380554 -0.629786 -0.629567 0.454989 -0.865406 -0.499639 0.0378628 -0.77264 -0.445913 0.451872 -0.965237 -0.258635 0.0377419 -0.863102 -0.231137 0.449032 -0.999289 7.95395e-08 0.0376982 -0.894697 0.000108208 0.446673 -0.965238 0.258635 0.0377393 -0.865012 0.231866 0.444964 -0.865406 0.499639 0.037863 -0.775945 0.448037 0.444041 -0.7066 0.706589 0.0380553 -0.633598 0.633592 0.443975 -0.499641 0.865385 0.038306 -0.447859 0.775626 0.444778 -0.258635 0.965204 0.0385965 -0.231677 0.864328 0.446388 -4.11673e-06 0.8577 -0.51415 -0.222073 0.82877 -0.513638 -0.42915 0.743303 -0.513159 -0.607081 0.607076 -0.512749 -0.743678 0.429364 -0.512435 -0.829582 0.222283 -0.512235 -0.858886 -3.24003e-08 -0.512166 -0.82958 -0.222283 -0.512237 -0.743679 -0.429364 -0.512433 -0.607081 -0.607077 -0.512748 -0.42915 -0.743302 -0.51316 -0.222073 -0.82877 -0.513638 -4.11673e-06 -0.8577 -0.514151 0.221904 -0.82818 -0.514661 0.428548 -0.742279 -0.515139 0.605892 -0.60589 -0.515551 0.741898 -0.428337 -0.515863 0.827365 -0.221696 -0.51606 0.856512 -6.46566e-08 -0.516127 0.827365 0.221696 -0.51606 0.741899 0.428337 -0.515862 0.605892 0.60589 -0.515549 0.428548 0.742278 -0.515141 0.221904 0.828179 -0.514663 -6.96336e-05 0.33171 0.943381 -0.0862012 0.321573 0.942953 0.0852966 0.318709 0.944007 0.16375 0.283863 0.944779 0.229868 0.230058 0.945639 0.279339 0.161434 0.946525 0.309195 0.0829799 0.947371 0.317879 0.000116986 0.948131 0.305256 -0.0816923 0.94876 0.272511 -0.157257 0.949214 0.221948 -0.2219 0.949473 -0.2274 -0.227215 0.946923 -0.15962 -0.276238 0.947742 -0.2807 -0.161905 0.946042 -0.315519 -0.084408 0.945158 -0.32898 0.000120808 0.944337 -0.31968 0.085766 0.943636 -0.287895 0.166299 0.943112 -0.235671 0.235723 0.942812 -0.166739 0.288801 0.942758 7.2509e-05 -0.133038 0.991111 0.0347919 -0.129561 0.990961 -0.0340933 -0.127496 0.991253 -0.0654674 -0.113507 0.991378 -0.0920833 -0.0921447 0.991479 -0.112334 -0.0648881 0.99155 -0.125028 -0.0335129 0.991587 -0.129426 8.23968e-06 0.991589 -0.125258 0.0335905 0.991555 -0.112733 0.0651351 0.991488 -0.0925488 0.0926272 0.99139 0.0968765 0.0968084 0.990577 0.0681148 0.117855 0.990692 0.119143 0.0687517 0.990494 0.133183 0.0356746 0.990449 0.137896 9.00272e-06 0.990447 0.132926 -0.0355873 0.990487 0.118698 -0.068477 0.990566 0.0963677 -0.0962826 0.990678 0.0676797 -0.117085 0.990813 0.441952 -0.765565 0.467534 0.499601 -0.865354 0.039516 0.228923 -0.854644 0.466024 0.25861 -0.965185 0.0392239 -0.000108537 -0.885905 0.463866 -1.02168e-05 -0.999243 0.0389106 -0.258636 -0.965203 0.0385975 -0.229778 -0.857033 0.46119 0.156848 -0.271667 0.949524 0.0812851 -0.303485 0.949363 -6.49802e-05 -0.315285 0.948997 -0.082119 -0.306114 0.948447 -0.0658751 0.114231 0.991268 -0.0343317 0.128406 0.991127 7.35953e-05 0.134027 0.990978 0.03504 0.1305 0.990829 0.230807 0.861902 0.4515 -0.000111246 0.89369 0.448685 -1.02282e-05 0.999243 0.0389102 0.25861 0.965185 0.0392236 0.445212 0.771428 0.454627 0.499601 0.865354 0.0395156 0.628533 0.628752 0.45784 0.706544 0.706551 0.0397642 0.768474 0.443849 0.460919 0.865331 0.499605 0.0399555 0.855793 0.229439 0.463656 0.965149 0.258613 0.0400791 0.884849 0.000106276 0.465878 0.999195 -1.36502e-07 0.04012 0.853917 -0.228725 0.467451 0.965149 -0.258613 0.0400757 0.765224 -0.441761 0.468273 0.865331 -0.499605 0.0399558 0.624775 -0.624781 0.468301 0.706543 -0.706552 0.0397663 -0.444563 -0.769706 0.458166 -0.499641 -0.865385 0.0383048 -0.7066 -0.706589 0.0380554 -0.629786 -0.629567 0.454989 -0.865406 -0.499639 0.0378628 -0.77264 -0.445913 0.451872 -0.965237 -0.258635 0.0377419 -0.863102 -0.231137 0.449032 -0.999289 7.95395e-08 0.0376982 -0.894697 0.000108208 0.446673 -0.965238 0.258635 0.0377393 -0.865012 0.231866 0.444964 -0.865406 0.499639 0.037863 -0.775945 0.448037 0.444041 -0.7066 0.706589 0.0380553 -0.633598 0.633592 0.443975 -0.499641 0.865385 0.038306 -0.447859 0.775626 0.444778 -0.258635 0.965204 0.0385965 -0.231677 0.864328 0.446388 -4.11673e-06 0.8577 -0.51415 -0.222073 0.82877 -0.513638 -0.42915 0.743303 -0.513159 -0.607081 0.607076 -0.512749 -0.743678 0.429364 -0.512435 -0.829582 0.222283 -0.512235 -0.858886 -3.24003e-08 -0.512166 -0.82958 -0.222283 -0.512237 -0.743679 -0.429364 -0.512433 -0.607081 -0.607077 -0.512748 -0.42915 -0.743302 -0.51316 -0.222073 -0.82877 -0.513638 -4.11673e-06 -0.8577 -0.514151 0.221904 -0.82818 -0.514661 0.428548 -0.742279 -0.515139 0.605892 -0.60589 -0.515551 0.741899 -0.428336 -0.515863 0.827365 -0.221697 -0.51606 0.856511 -7.75879e-08 -0.516128 0.827364 0.221696 -0.516061 0.741899 0.428337 -0.515862 0.605892 0.60589 -0.515549 0.428548 0.742278 -0.515141 0.221904 0.828179 -0.514663 -6.96325e-05 0.33171 0.943381 -0.0862012 0.321573 0.942953 0.0852966 0.318709 0.944007 0.16375 0.283863 0.944779 0.229869 0.230058 0.945639 0.279339 0.161434 0.946524 0.309195 0.0829801 0.947372 0.317878 0.000116936 0.948132 0.305257 -0.0816928 0.94876 0.272511 -0.157258 0.949214 0.221948 -0.2219 0.949473 -0.2274 -0.227215 0.946923 -0.15962 -0.276238 0.947742 -0.2807 -0.161905 0.946042 -0.315519 -0.084408 0.945158 -0.32898 0.000120808 0.944337 -0.31968 0.085766 0.943636 -0.287895 0.166299 0.943112 -0.235671 0.235723 0.942812 -0.166739 0.288801 0.942758 7.2509e-05 -0.133038 0.991111 0.0347919 -0.129561 0.990961 -0.0340933 -0.127496 0.991253 -0.0654674 -0.113507 0.991378 -0.0920833 -0.0921447 0.991479 -0.112334 -0.0648881 0.99155 -0.125028 -0.0335128 0.991587 -0.129426 8.23036e-06 0.991589 -0.125258 0.0335904 0.991555 -0.112733 0.0651351 0.991488 -0.0925488 0.0926272 0.99139 0.0968765 0.0968084 0.990577 0.0681148 0.117855 0.990692 0.119143 0.0687517 0.990494 0.133183 0.0356746 0.990449 0.137896 9.00272e-06 0.990447 0.132926 -0.0355873 0.990487 0.118698 -0.068477 0.990566 0.0963677 -0.0962826 0.990678 0.0676797 -0.117085 0.990813 0.441952 -0.765565 0.467534 0.499601 -0.865354 0.039516 0.228923 -0.854644 0.466024 0.25861 -0.965185 0.0392239 -0.000108537 -0.885906 0.463866 -1.02206e-05 -0.999243 0.0389106 -0.258636 -0.965203 0.0385975 -0.229778 -0.857033 0.46119 0.156848 -0.271667 0.949524 0.0812851 -0.303485 0.949363 -6.49791e-05 -0.315285 0.948997 -0.082119 -0.306114 0.948447 -0.0658751 0.114231 0.991268 -0.0343317 0.128406 0.991127 7.35953e-05 0.134027 0.990978 0.03504 0.1305 0.990829 0.230807 0.861902 -0.4515 0.25861 0.965185 -0.0392236 -1.02244e-05 0.999243 -0.0389102 -0.000111246 0.89369 -0.448685 0.445212 0.771428 -0.454627 0.499601 0.865354 -0.0395156 0.628532 0.628753 -0.45784 0.706543 0.706552 -0.0397639 0.768473 0.443849 -0.460919 0.865331 0.499605 -0.0399555 0.855793 0.229438 -0.463655 0.965149 0.258613 -0.0400796 0.884849 0.000106331 -0.465878 0.999195 -1.21335e-07 -0.0401205 0.853917 -0.228725 -0.467451 0.965149 -0.258613 -0.0400757 0.765224 -0.44176 -0.468273 0.865331 -0.499605 -0.0399555 0.624774 -0.624781 -0.468301 0.706543 -0.706552 -0.0397663 -0.444563 -0.769706 -0.458166 -0.629786 -0.629567 -0.454989 -0.7066 -0.706589 -0.0380554 -0.499641 -0.865385 -0.0383048 -0.77264 -0.445913 -0.451872 -0.865406 -0.499639 -0.0378628 -0.863102 -0.231137 -0.449032 -0.965237 -0.258635 -0.0377419 -0.894697 0.000108208 -0.446673 -0.999289 7.95395e-08 -0.0376982 -0.865012 0.231866 -0.444964 -0.965238 0.258635 -0.0377393 -0.775945 0.448037 -0.444041 -0.865406 0.499639 -0.037863 -0.633598 0.633592 -0.443975 -0.7066 0.706589 -0.0380553 -0.447859 0.775626 -0.444778 -0.499641 0.865385 -0.0383061 -0.231677 0.864328 -0.446388 -0.258635 0.965204 -0.0385965 -4.11673e-06 0.8577 0.51415 0.221904 0.828179 0.514663 0.428548 0.742278 0.515141 0.605892 0.60589 0.515549 0.741899 0.428337 0.515862 0.827365 0.221696 0.51606 0.856512 -6.46566e-08 0.516127 0.827365 -0.221696 0.51606 0.741899 -0.428337 0.515863 0.605892 -0.60589 0.515551 0.428548 -0.742279 0.515139 0.221904 -0.82818 0.514661 -4.11673e-06 -0.8577 0.514151 -0.222073 -0.82877 0.513638 -0.42915 -0.743302 0.51316 -0.607081 -0.607077 0.512748 -0.743679 -0.429364 0.512433 -0.82958 -0.222283 0.512237 -0.858886 -3.24003e-08 0.512166 -0.829582 0.222283 0.512235 -0.743678 0.429364 0.512435 -0.607081 0.607076 0.512749 -0.42915 0.743303 0.513159 -0.222073 0.82877 0.513638 -0.0862012 0.321573 -0.942953 -6.9633e-05 0.33171 -0.943381 0.0852966 0.318709 -0.944007 0.16375 0.283863 -0.944779 0.229868 0.230058 -0.945639 0.279339 0.161434 -0.946525 0.309195 0.0829799 -0.947371 0.317879 0.000116988 -0.948131 0.305256 -0.0816923 -0.94876 0.272511 -0.157257 -0.949214 0.221948 -0.2219 -0.949473 -0.15962 -0.276238 -0.947742 -0.2274 -0.227215 -0.946923 -0.2807 -0.161904 -0.946042 -0.315519 -0.084408 -0.945158 -0.32898 0.000120808 -0.944337 -0.31968 0.085766 -0.943636 -0.287895 0.166299 -0.943112 -0.235671 0.235723 -0.942812 -0.166739 0.288801 -0.942758 0.0347919 -0.129561 -0.990961 7.2509e-05 -0.133038 -0.991111 -0.0340933 -0.127496 -0.991253 -0.0654674 -0.113507 -0.991378 -0.0920833 -0.0921447 -0.991479 -0.112334 -0.0648881 -0.99155 -0.125028 -0.0335129 -0.991587 -0.129426 8.23968e-06 -0.991589 -0.125258 0.0335905 -0.991555 -0.112733 0.0651351 -0.991488 -0.0925488 0.0926272 -0.99139 0.0681148 0.117855 -0.990692 0.0968765 0.0968084 -0.990577 0.119143 0.0687517 -0.990494 0.133183 0.0356746 -0.990449 0.137896 9.00272e-06 -0.990447 0.132926 -0.0355873 -0.990487 0.118698 -0.068477 -0.990566 0.0963677 -0.0962826 -0.990678 0.0676797 -0.117085 -0.990813 0.441952 -0.765565 -0.467534 0.499601 -0.865354 -0.039516 0.228923 -0.854644 -0.466024 0.25861 -0.965185 -0.0392239 -0.000108537 -0.885905 -0.463866 -1.02168e-05 -0.999243 -0.0389106 -0.229778 -0.857033 -0.46119 -0.258636 -0.965203 -0.0385975 0.156848 -0.271667 -0.949524 0.0812851 -0.303485 -0.949363 -6.49802e-05 -0.315285 -0.948997 -0.082119 -0.306114 -0.948447 -0.0658751 0.114231 -0.991268 -0.0343317 0.128406 -0.991127 7.35953e-05 0.134027 -0.990978 0.03504 0.1305 -0.990829 0.230807 0.861902 -0.4515 0.25861 0.965185 -0.0392236 -1.02282e-05 0.999243 -0.0389102 -0.000111246 0.89369 -0.448685 0.445212 0.771428 -0.454627 0.499601 0.865354 -0.0395156 0.628533 0.628752 -0.45784 0.706544 0.706551 -0.0397641 0.768474 0.443849 -0.460919 0.865331 0.499605 -0.0399555 0.855793 0.229439 -0.463656 0.965149 0.258613 -0.0400791 0.884849 0.000106276 -0.465878 0.999195 -1.3271e-07 -0.04012 0.853917 -0.228725 -0.467451 0.965149 -0.258613 -0.0400757 0.765224 -0.441761 -0.468273 0.865331 -0.499605 -0.0399558 0.624775 -0.624781 -0.468301 0.706543 -0.706552 -0.0397663 -0.444563 -0.769706 -0.458166 -0.629786 -0.629567 -0.454989 -0.7066 -0.706589 -0.0380554 -0.499641 -0.865385 -0.0383048 -0.77264 -0.445913 -0.451872 -0.865406 -0.499639 -0.0378628 -0.863102 -0.231137 -0.449032 -0.965237 -0.258635 -0.0377419 -0.894697 0.000108208 -0.446673 -0.999289 7.95395e-08 -0.0376982 -0.865012 0.231866 -0.444964 -0.965238 0.258635 -0.0377393 -0.775945 0.448037 -0.444041 -0.865406 0.499639 -0.037863 -0.633598 0.633592 -0.443975 -0.7066 0.706589 -0.0380553 -0.447859 0.775626 -0.444778 -0.499641 0.865385 -0.0383061 -0.231677 0.864328 -0.446388 -0.258635 0.965204 -0.0385965 -4.11673e-06 0.8577 0.51415 0.221904 0.828179 0.514663 0.428548 0.742278 0.515141 0.605892 0.60589 0.515549 0.741899 0.428337 0.515862 0.827364 0.221696 0.516061 0.856511 -7.75879e-08 0.516128 0.827365 -0.221697 0.51606 0.741899 -0.428336 0.515863 0.605892 -0.60589 0.515551 0.428548 -0.742279 0.515139 0.221904 -0.82818 0.514661 -4.11673e-06 -0.8577 0.514151 -0.222073 -0.82877 0.513638 -0.42915 -0.743302 0.51316 -0.607081 -0.607077 0.512748 -0.743679 -0.429364 0.512433 -0.82958 -0.222283 0.512237 -0.858886 -3.24003e-08 0.512166 -0.829582 0.222283 0.512235 -0.743678 0.429364 0.512435 -0.607081 0.607076 0.512749 -0.42915 0.743303 0.513159 -0.222073 0.82877 0.513638 -0.0862012 0.321573 -0.942953 -6.9633e-05 0.33171 -0.943381 0.0852966 0.318709 -0.944007 0.16375 0.283863 -0.944779 0.229869 0.230058 -0.945639 0.279339 0.161434 -0.946524 0.309195 0.0829801 -0.947372 0.317878 0.000116934 -0.948132 0.305256 -0.0816928 -0.94876 0.272511 -0.157258 -0.949214 0.221948 -0.2219 -0.949473 -0.15962 -0.276238 -0.947742 -0.2274 -0.227215 -0.946923 -0.2807 -0.161905 -0.946042 -0.315519 -0.084408 -0.945158 -0.32898 0.000120809 -0.944337 -0.31968 0.085766 -0.943636 -0.287895 0.166299 -0.943112 -0.235671 0.235723 -0.942812 -0.166739 0.288801 -0.942758 0.0347919 -0.129561 -0.990961 7.2509e-05 -0.133038 -0.991111 -0.0340933 -0.127496 -0.991253 -0.0654674 -0.113507 -0.991378 -0.0920833 -0.0921447 -0.991479 -0.112334 -0.0648881 -0.99155 -0.125028 -0.0335128 -0.991587 -0.129426 8.23036e-06 -0.991589 -0.125258 0.0335904 -0.991555 -0.112733 0.0651351 -0.991488 -0.0925488 0.0926272 -0.99139 0.0681148 0.117855 -0.990692 0.0968765 0.0968084 -0.990577 0.119143 0.0687517 -0.990494 0.133183 0.0356746 -0.990449 0.137896 9.00272e-06 -0.990447 0.132926 -0.0355873 -0.990487 0.118698 -0.068477 -0.990566 0.0963677 -0.0962826 -0.990678 0.0676797 -0.117085 -0.990813 0.441952 -0.765565 -0.467534 0.499601 -0.865354 -0.039516 0.228923 -0.854644 -0.466024 0.25861 -0.965185 -0.0392239 -0.000108537 -0.885906 -0.463866 -1.02206e-05 -0.999243 -0.0389106 -0.229778 -0.857033 -0.46119 -0.258636 -0.965203 -0.0385975 0.156848 -0.271667 -0.949524 0.0812851 -0.303485 -0.949363 -6.49796e-05 -0.315285 -0.948997 -0.082119 -0.306114 -0.948447 -0.0658751 0.114231 -0.991268 -0.0343317 0.128406 -0.991127 7.35953e-05 0.134027 -0.990978 0.03504 0.1305 -0.990829 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

3 1 0 50 3 0 3 2 1 2 3 10 50 49 3 10 3 49 1 2 9 1 9 8 2 10 9 10 49 54 54 49 50 54 50 53 7 5 4 7 6 5 52 6 7 52 7 51 11 15 14 11 14 13 13 12 11 15 11 36 34 33 15 36 34 15 36 30 31 36 31 35 36 35 34 32 31 30 32 30 29 32 29 17 32 17 18 32 18 28 32 28 27 32 27 26 19 18 17 19 17 16 25 19 16 25 16 24 25 24 23 25 23 22 25 22 21 25 21 20 40 38 37 40 39 38 42 39 40 42 40 41 46 44 43 48 46 43 48 43 47 46 45 44 55 59 58 55 58 57 57 56 55 78 77 55 78 55 56 56 80 79 56 79 78 78 72 73 78 73 77 74 73 72 74 72 71 75 63 74 75 74 71 71 70 75 70 76 75 75 62 63 63 62 61 63 61 60 67 60 61 67 61 65 67 66 60 64 68 67 67 65 64 64 69 68 84 82 81 84 83 82 82 83 86 82 86 85 90 88 87 87 88 92 87 92 91 90 89 88 96 94 93 98 96 93 98 93 97 94 159 93 93 159 160 93 160 97 100 98 97 154 155 98 154 98 100 155 96 98 100 97 99 97 160 161 97 161 99 159 180 160 160 180 181 160 181 161 99 161 162 161 181 182 161 182 162 102 100 99 102 99 101 99 162 101 101 162 163 162 182 183 162 183 163 104 102 101 104 101 103 101 163 103 152 153 102 152 102 104 153 100 102 106 104 103 151 152 104 151 104 106 106 103 105 103 163 164 103 164 105 108 106 105 150 151 106 150 106 108 133 152 151 133 151 150 133 153 152 133 156 155 133 155 154 133 154 153 133 150 149 133 149 148 133 148 147 133 147 146 133 146 145 133 145 144 133 144 143 133 143 142 133 142 141 133 141 140 133 140 139 133 139 138 133 138 137 133 137 136 133 136 135 135 134 133 156 133 95 95 133 134 127 136 137 127 137 125 125 137 138 129 135 136 129 136 127 131 134 135 131 135 129 95 134 131 96 95 94 94 95 131 156 95 96 155 156 96 132 131 129 94 131 132 130 129 127 132 129 130 158 94 132 176 158 132 176 132 130 158 157 94 94 157 159 178 157 158 196 178 158 196 158 176 175 176 130 195 196 176 195 176 175 174 175 128 175 130 128 194 195 175 194 175 174 173 174 126 174 128 126 193 194 174 193 174 173 128 127 125 128 125 126 130 127 128 126 125 123 126 123 124 173 126 124 125 138 123 124 123 121 123 138 139 123 139 121 124 121 122 172 173 124 172 124 122 122 121 119 121 139 140 121 140 119 122 119 120 171 172 122 171 122 120 191 192 172 191 172 171 192 173 172 192 193 173 170 171 120 190 191 171 190 171 170 168 170 118 170 120 118 188 190 170 188 170 168 169 168 116 168 118 116 189 188 168 189 168 169 118 117 115 118 115 116 120 117 118 116 115 114 116 114 113 169 116 113 117 142 115 115 142 143 115 143 114 113 114 203 114 143 144 114 144 203 113 203 204 208 169 113 208 113 204 204 203 202 203 144 145 203 145 202 204 202 201 207 208 204 207 204 201 211 212 208 211 208 207 212 169 208 212 189 169 199 206 207 199 207 201 206 211 207 202 199 201 200 197 199 202 200 199 197 206 199 197 205 206 205 210 206 206 210 211 198 111 197 200 198 197 111 205 197 145 146 200 145 200 202 146 198 200 198 112 111 146 147 198 147 112 198 112 109 111 109 167 111 111 167 205 112 110 109 148 110 112 147 148 112 110 107 109 107 166 109 109 166 167 166 187 167 167 187 209 167 209 205 107 165 166 165 186 166 166 186 187 105 164 165 105 165 107 164 185 165 165 185 186 108 105 107 110 108 107 149 150 108 149 108 110 148 149 110 164 184 185 163 184 164 163 183 184 205 209 210 117 141 142 120 119 117 119 141 117 119 140 141 178 177 157 157 177 179 157 179 159 159 179 180 153 154 100 216 214 213 218 216 213 218 213 217 214 279 213 213 279 280 213 280 217 220 218 217 274 275 218 274 218 220 275 216 218 220 217 219 217 280 281 217 281 219 279 300 280 280 300 301 280 301 281 219 281 282 281 301 302 281 302 282 222 220 219 222 219 221 219 282 221 221 282 283 282 302 303 282 303 283 224 222 221 224 221 223 221 283 223 272 273 222 272 222 224 273 220 222 226 224 223 271 272 224 271 224 226 226 223 225 223 283 284 223 284 225 228 226 225 270 271 226 270 226 228 253 272 271 253 271 270 253 273 272 253 276 275 253 275 274 253 274 273 253 270 269 253 269 268 253 268 267 253 267 266 253 266 265 253 265 264 253 264 263 253 263 262 253 262 261 253 261 260 253 260 259 253 259 258 253 258 257 253 257 256 253 256 255 255 254 253 276 253 215 215 253 254 247 256 257 247 257 245 245 257 258 249 255 256 249 256 247 251 254 255 251 255 249 215 254 251 216 215 214 214 215 251 276 215 216 275 276 216 252 251 249 214 251 252 250 249 247 252 249 250 278 214 252 296 278 252 296 252 250 278 277 214 214 277 279 298 277 278 316 298 278 316 278 296 295 296 250 315 316 296 315 296 295 294 295 248 295 250 248 314 315 295 314 295 294 293 294 246 294 248 246 313 314 294 313 294 293 248 247 245 248 245 246 250 247 248 246 245 243 246 243 244 293 246 244 245 258 243 244 243 241 243 258 259 243 259 241 244 241 242 292 293 244 292 244 242 242 241 239 241 259 260 241 260 239 242 239 240 291 292 242 291 242 240 311 312 292 311 292 291 312 293 292 312 313 293 290 291 240 310 311 291 310 291 290 288 290 238 290 240 238 308 310 290 308 290 288 289 288 236 288 238 236 309 308 288 309 288 289 238 237 235 238 235 236 240 237 238 236 235 234 236 234 233 289 236 233 237 262 235 235 262 263 235 263 234 233 234 323 234 263 264 234 264 323 233 323 324 328 289 233 328 233 324 324 323 322 323 264 265 323 265 322 324 322 321 327 328 324 327 324 321 331 332 328 331 328 327 332 289 328 332 309 289 319 326 327 319 327 321 326 331 327 322 319 321 320 317 319 322 320 319 317 326 319 317 325 326 325 330 326 326 330 331 318 231 317 320 318 317 231 325 317 265 266 320 265 320 322 266 318 320 318 232 231 266 267 318 267 232 318 232 229 231 229 287 231 231 287 325 232 230 229 268 230 232 267 268 232 230 227 229 227 286 229 229 286 287 286 307 287 287 307 329 287 329 325 227 285 286 285 306 286 286 306 307 225 284 285 225 285 227 284 305 285 285 305 306 228 225 227 230 228 227 269 270 228 269 228 230 268 269 230 284 304 305 283 304 284 283 303 304 325 329 330 237 261 262 240 239 237 239 261 237 239 260 261 298 297 277 277 297 299 277 299 279 279 299 300 273 274 220 336 334 333 333 334 338 333 338 337 399 336 333 400 399 333 400 333 337 337 338 340 338 375 376 338 376 340 334 375 338 337 340 339 401 400 337 401 337 339 420 399 400 421 420 400 421 400 401 402 401 339 422 421 401 422 401 402 339 340 342 339 342 341 402 339 341 403 402 341 423 422 402 423 402 403 341 342 344 341 344 343 403 341 343 342 377 378 342 378 344 340 377 342 343 344 346 344 378 379 344 379 346 343 346 345 404 403 343 404 343 345 345 346 348 346 379 380 346 380 348 373 380 379 373 379 378 373 378 377 373 396 395 373 395 394 373 394 393 373 393 392 373 392 391 373 391 390 373 390 389 373 389 388 373 388 387 373 387 386 373 386 385 373 385 384 373 384 383 373 383 382 373 382 381 373 381 380 373 377 376 373 376 375 375 374 373 335 373 374 396 373 335 348 380 381 345 348 347 347 348 350 348 381 350 405 404 345 405 345 347 347 350 349 406 405 347 406 347 349 349 350 352 350 381 382 350 382 352 349 352 351 407 406 349 407 349 351 426 405 406 427 426 406 427 406 407 445 407 351 449 427 407 449 407 445 351 352 438 351 438 437 445 351 437 446 445 437 450 449 445 450 445 446 437 438 440 437 440 439 446 437 439 438 383 384 438 384 440 352 383 438 439 440 442 440 384 385 440 385 442 439 442 441 447 446 439 447 439 441 442 444 443 442 443 441 385 444 442 385 386 444 444 356 353 444 353 443 386 356 444 443 448 447 443 447 441 353 448 443 451 446 447 448 451 447 353 408 448 448 452 451 408 452 448 356 354 353 354 408 353 354 409 408 409 428 408 408 428 452 356 355 354 355 357 354 357 409 354 357 410 409 409 429 428 410 429 409 355 358 357 358 359 357 359 410 357 388 358 355 387 388 355 387 355 356 358 360 359 389 360 358 388 389 358 360 361 359 359 411 410 361 411 359 360 362 361 390 362 360 389 390 360 362 363 361 361 412 411 363 412 361 411 431 430 411 430 410 412 431 411 363 413 412 412 432 431 413 432 412 365 414 413 365 413 363 413 433 432 414 433 413 364 366 365 364 365 363 366 367 365 367 414 365 367 415 414 414 434 433 415 434 414 366 368 367 368 369 367 369 415 367 393 368 366 392 393 366 392 366 364 368 370 369 394 370 368 393 394 368 370 371 369 369 416 415 371 416 369 370 372 371 395 372 370 394 395 370 372 336 371 336 397 371 371 397 416 416 436 435 416 435 415 397 436 416 336 398 397 398 417 397 397 417 436 399 398 336 398 418 417 419 418 398 419 398 399 420 419 399 336 335 334 372 335 336 335 374 334 396 335 372 334 374 375 395 396 372 415 435 434 362 364 363 391 392 364 391 364 362 390 391 362 410 430 429 386 387 356 451 450 446 352 382 383 426 425 405 425 424 404 425 404 405 424 423 403 424 403 404 340 376 377 456 454 453 453 454 458 453 458 457 519 456 453 520 519 453 520 453 457 457 458 460 458 495 496 458 496 460 454 495 458 457 460 459 521 520 457 521 457 459 540 519 520 541 540 520 541 520 521 522 521 459 542 541 521 542 521 522 459 460 462 459 462 461 522 459 461 523 522 461 543 542 522 543 522 523 461 462 464 461 464 463 523 461 463 462 497 498 462 498 464 460 497 462 463 464 466 464 498 499 464 499 466 463 466 465 524 523 463 524 463 465 465 466 468 466 499 500 466 500 468 493 500 499 493 499 498 493 498 497 493 516 515 493 515 514 493 514 513 493 513 512 493 512 511 493 511 510 493 510 509 493 509 508 493 508 507 493 507 506 493 506 505 493 505 504 493 504 503 493 503 502 493 502 501 493 501 500 493 497 496 493 496 495 495 494 493 455 493 494 516 493 455 468 500 501 465 468 467 467 468 470 468 501 470 525 524 465 525 465 467 467 470 469 526 525 467 526 467 469 469 470 472 470 501 502 470 502 472 469 472 471 527 526 469 527 469 471 546 525 526 547 546 526 547 526 527 565 527 471 569 547 527 569 527 565 471 472 558 471 558 557 565 471 557 566 565 557 570 569 565 570 565 566 557 558 560 557 560 559 566 557 559 558 503 504 558 504 560 472 503 558 559 560 562 560 504 505 560 505 562 559 562 561 567 566 559 567 559 561 562 564 563 562 563 561 505 564 562 505 506 564 564 476 473 564 473 563 506 476 564 563 568 567 563 567 561 473 568 563 571 566 567 568 571 567 473 528 568 568 572 571 528 572 568 476 474 473 474 528 473 474 529 528 529 548 528 528 548 572 476 475 474 475 477 474 477 529 474 477 530 529 529 549 548 530 549 529 475 478 477 478 479 477 479 530 477 508 478 475 507 508 475 507 475 476 478 480 479 509 480 478 508 509 478 480 481 479 479 531 530 481 531 479 480 482 481 510 482 480 509 510 480 482 483 481 481 532 531 483 532 481 531 551 550 531 550 530 532 551 531 483 533 532 532 552 551 533 552 532 485 534 533 485 533 483 533 553 552 534 553 533 484 486 485 484 485 483 486 487 485 487 534 485 487 535 534 534 554 553 535 554 534 486 488 487 488 489 487 489 535 487 513 488 486 512 513 486 512 486 484 488 490 489 514 490 488 513 514 488 490 491 489 489 536 535 491 536 489 490 492 491 515 492 490 514 515 490 492 456 491 456 517 491 491 517 536 536 556 555 536 555 535 517 556 536 456 518 517 518 537 517 517 537 556 519 518 456 518 538 537 539 538 518 539 518 519 540 539 519 456 455 454 492 455 456 455 494 454 516 455 492 454 494 495 515 516 492 535 555 554 482 484 483 511 512 484 511 484 482 510 511 482 530 550 549 506 507 476 571 570 566 472 502 503 546 545 525 545 544 524 545 524 525 544 543 523 544 523 524 460 496 497

+
+
+
+ + + + -0.338626 0.181558 0.43665 -0.338626 0.181558 0.837 0.0767244 0.181558 0.837 0.0767244 0.181558 0.426 0.0767244 0.181558 -0 -0.338626 0.181558 -0 0.774923 0.181558 0.837 0.774923 0.181558 0.431917 0.774923 0.181558 -0 -1.26305 0.995218 0.50481 -1.22577 0.998413 0.61131 -1.27345 0.99584 0.609727 -1.36468 0.992329 0.504638 1.70191 0.230016 0.451793 1.70189 0.227264 0.797316 1.89574 0.243418 0.77749 2.04165 0.263563 0.648585 2.11087 0.283798 0.4686 -0.915882 0.181558 0.429195 -0.915882 0.187412 0.832316 -1.64429 0.198015 0.429195 -2.0799 0.217768 0.5112 -1.79981 0.204988 0.82005 -1.64429 0.200153 0.828914 2.14495 0.285928 -0 1.33342 0.181558 -0 1.33342 0.181558 0.429195 1.7019 0.230015 0.429195 1.7019 0.230015 0.451793 -1.30778 0.181558 -0 -2.16404 0.227353 -0 -2.1196 0.22229 0.27 0.973484 0.181558 0.837 0.973484 0.181558 0.4336 0.973484 0.181558 0.429195 -0.915882 0.181558 0.429195 -1.27637 0.181558 0.429195 -1.64429 0.198556 0.429195 -1.64432 0.315748 0.429195 -1.61659 0.455133 0.429195 -1.53764 0.573297 0.429195 -1.41947 0.652252 0.429195 -1.28009 0.679978 0.429195 -1.1407 0.652252 0.429195 -1.02254 0.573297 0.429195 -0.943581 0.455133 0.429195 -0.915856 0.315748 0.429195 -1.1407 0.652252 0.429195 -1.28009 0.679978 0.429195 -1.28009 0.679978 0.824905 -1.25457 0.674902 0.827382 -1.1407 0.652252 0.833201 -1.41947 0.652252 0.429195 -1.41947 0.652252 0.818487 -1.28009 0.679978 0.824838 -1.53764 0.573297 0.81961 -1.41947 0.652252 0.817901 -1.53764 0.573297 0.429195 -1.61659 0.455133 0.829836 -1.53764 0.573297 0.820185 -1.61659 0.455133 0.429195 -1.64432 0.315748 0.429195 -1.64432 0.315748 0.828802 -1.61723 0.451921 0.830215 -1.61659 0.455133 0.829849 -1.64429 0.198275 0.429195 -1.64429 0.198015 0.429195 -1.64429 0.200153 0.828914 -1.64432 0.315748 0.828787 -0.915856 0.315748 0.429195 -0.915856 0.315748 0.851355 -0.915882 0.187412 0.832316 -0.915882 0.181558 0.429195 -0.943581 0.455133 0.429195 -0.943581 0.455133 0.854905 -0.915856 0.315748 0.851066 -1.02254 0.573297 0.429195 -1.02254 0.573297 0.845107 -0.967871 0.491485 0.855431 -0.943581 0.455133 0.854613 -1.02254 0.573297 0.845117 0.973484 0.181558 0.429195 0.973454 0.315748 0.429195 1.00118 0.455133 0.429195 1.08013 0.573297 0.429195 1.1983 0.652252 0.429195 1.33768 0.679978 0.429195 1.47707 0.652252 0.429195 1.59523 0.573297 0.429195 1.67419 0.455133 0.429195 1.70191 0.315748 0.429195 1.7019 0.229921 0.429195 1.33342 0.181558 0.429195 1.33768 0.679978 0.429195 1.33768 0.679978 0.850203 1.47707 0.652252 0.830695 1.47707 0.652252 0.429195 1.1983 0.652252 0.429195 1.1983 0.652252 0.858539 1.32551 0.677556 0.852 1.33768 0.679978 0.850072 1.08013 0.573297 0.860471 1.1983 0.652252 0.858385 1.08013 0.573297 0.429195 1.00118 0.455133 0.429195 1.00118 0.455133 0.858206 1.08013 0.573297 0.860887 0.973454 0.315748 0.429195 0.973454 0.315748 0.856591 1.00118 0.455133 0.86136 0.973484 0.181558 0.429195 0.973484 0.181558 0.4336 0.973484 0.181558 0.837 0.973454 0.315748 0.85771 1.70191 0.315748 0.813776 1.70189 0.227264 0.797316 1.7019 0.230015 0.451793 1.7019 0.229961 0.429195 1.70191 0.315748 0.429195 1.67419 0.455133 0.429195 1.67419 0.455133 0.808532 1.70191 0.315748 0.814677 1.59523 0.573297 0.429195 1.59523 0.573297 0.816838 1.67419 0.455133 0.811591 1.59523 0.573297 0.817803 -1.3048 0.995218 0.27 -1.45673 0.991344 0.27 -1.32256 0.995218 -0 -1.48283 0.990212 -0 -2.03976 0.297631 0.27 -2.04668 0.394131 0.27 -2.0127 0.393706 0.44943 -1.99779 0.301264 0.47073 -2.07276 0.394771 -0 -2.07276 0.292744 -0 -1.27637 0.181558 0.429195 -0.338626 0.181558 -0.43665 0.0767244 0.181558 -0.426 0.0767244 0.181558 -0.837 -0.338626 0.181558 -0.837 0.774923 0.181558 -0.431917 0.774923 0.181558 -0.837 -1.26305 0.995218 -0.50481 -1.36468 0.992329 -0.504638 -1.27345 0.99584 -0.609727 -1.22577 0.998413 -0.61131 1.70191 0.230016 -0.451793 2.11087 0.283798 -0.4686 2.04165 0.263563 -0.648585 1.89574 0.243418 -0.77749 1.70189 0.227264 -0.797316 -0.915882 0.187412 -0.832316 -0.915882 0.181558 -0.429195 -1.64429 0.198015 -0.429195 -1.64429 0.200153 -0.828914 -1.79981 0.204988 -0.82005 -2.0799 0.217768 -0.5112 1.7019 0.230015 -0.451793 1.7019 0.230015 -0.429195 1.33342 0.181558 -0.429195 -2.1196 0.22229 -0.27 0.973484 0.181558 -0.4336 0.973484 0.181558 -0.837 0.973484 0.181558 -0.429195 -0.915882 0.181558 -0.429195 -0.915856 0.315748 -0.429195 -0.943581 0.455133 -0.429195 -1.02254 0.573297 -0.429195 -1.1407 0.652252 -0.429195 -1.28009 0.679978 -0.429195 -1.41947 0.652252 -0.429195 -1.53764 0.573297 -0.429195 -1.61659 0.455133 -0.429195 -1.64432 0.315748 -0.429195 -1.64429 0.198556 -0.429195 -1.27637 0.181558 -0.429195 -1.1407 0.652252 -0.429195 -1.1407 0.652252 -0.833201 -1.25457 0.674902 -0.827382 -1.28009 0.679978 -0.824905 -1.28009 0.679978 -0.429195 -1.28009 0.679978 -0.824838 -1.41947 0.652252 -0.818487 -1.41947 0.652252 -0.429195 -1.53764 0.573297 -0.81961 -1.53764 0.573297 -0.429195 -1.41947 0.652252 -0.817901 -1.61659 0.455133 -0.829836 -1.61659 0.455133 -0.429195 -1.53764 0.573297 -0.820185 -1.61659 0.455133 -0.829849 -1.61723 0.451921 -0.830215 -1.64432 0.315748 -0.828802 -1.64432 0.315748 -0.429195 -1.64432 0.315748 -0.828787 -1.64429 0.200153 -0.828914 -1.64429 0.198015 -0.429195 -1.64429 0.198275 -0.429195 -0.915856 0.315748 -0.429195 -0.915882 0.181558 -0.429195 -0.915882 0.187412 -0.832316 -0.915856 0.315748 -0.851355 -0.943581 0.455133 -0.429195 -0.915856 0.315748 -0.851066 -0.943581 0.455133 -0.854905 -0.943581 0.455133 -0.854613 -0.967871 0.491485 -0.855431 -1.02254 0.573297 -0.845107 -1.02254 0.573297 -0.429195 -1.02254 0.573297 -0.845117 0.973484 0.181558 -0.429195 1.33342 0.181558 -0.429195 1.7019 0.229921 -0.429195 1.70191 0.315748 -0.429195 1.67419 0.455133 -0.429195 1.59523 0.573297 -0.429195 1.47707 0.652252 -0.429195 1.33768 0.679978 -0.429195 1.1983 0.652252 -0.429195 1.08013 0.573297 -0.429195 1.00118 0.455133 -0.429195 0.973454 0.315748 -0.429195 1.33768 0.679978 -0.429195 1.47707 0.652252 -0.429195 1.47707 0.652252 -0.830695 1.33768 0.679978 -0.850203 1.1983 0.652252 -0.429195 1.33768 0.679978 -0.850072 1.32551 0.677556 -0.852 1.1983 0.652252 -0.858539 1.08013 0.573297 -0.860471 1.08013 0.573297 -0.429195 1.1983 0.652252 -0.858385 1.08013 0.573297 -0.860887 1.00118 0.455133 -0.858206 1.00118 0.455133 -0.429195 1.00118 0.455133 -0.86136 0.973454 0.315748 -0.856591 0.973454 0.315748 -0.429195 0.973454 0.315748 -0.85771 0.973484 0.181558 -0.837 0.973484 0.181558 -0.4336 0.973484 0.181558 -0.429195 1.70191 0.315748 -0.813776 1.70191 0.315748 -0.429195 1.7019 0.229961 -0.429195 1.7019 0.230015 -0.451793 1.70189 0.227264 -0.797316 1.70191 0.315748 -0.814677 1.67419 0.455133 -0.808532 1.67419 0.455133 -0.429195 1.59523 0.573297 -0.429195 1.67419 0.455133 -0.811591 1.59523 0.573297 -0.816838 1.59523 0.573297 -0.817803 -1.3048 0.995218 -0.27 -1.45673 0.991344 -0.27 -2.03976 0.297631 -0.27 -1.99779 0.301264 -0.47073 -2.0127 0.393706 -0.44943 -2.04668 0.394131 -0.27 -1.27637 0.181558 -0.429195 + + + + + + + + + + 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 -0.0269333 0.999607 -0.00775956 -0.0283763 0.999396 -0.0200495 -0.0283763 0.999396 -0.0200495 -0.0269333 0.999607 -0.00775956 0.129131 -0.991626 -0.00156163 0.130699 -0.991391 -0.00789167 0.130699 -0.991391 -0.00789167 0.130699 -0.991391 -0.00789167 0.129131 -0.991626 -0.00156163 0 -1 -0 0 -1 -0 -0.0444897 -0.999001 0.00430708 -0.0474625 -0.998873 -0.000439597 -0.0442945 -0.999004 0.00534453 -0.0442945 -0.999004 0.00534453 0.127558 -0.991831 -0 0.0639095 -0.997956 -0 0.0639093 -0.997953 0.00238913 0.127557 -0.99182 0.00476847 0.129131 -0.991626 -0.00156163 -0.0245299 -0.999699 -2.91131e-11 -0.0534062 -0.998573 -0 -0.0534036 -0.998524 -0.0099329 0 -1 -0 0 -1 -0 0 -1 -0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.382683 -0.92388 -0 -7.59655e-08 -1 -0 -7.59655e-08 -1 -0 -0.19509 -0.980785 -0 -0.382683 -0.92388 -0 0.382684 -0.92388 -0 0.19509 -0.980785 -0 -7.59655e-08 -1 -0 0.555571 -0.831469 -0 0.555571 -0.831469 -0 0.707107 -0.707107 -0 0.92388 -0.382684 -0 0.831469 -0.555571 -0 0.92388 -0.382684 -0 0.995195 -0.097909 -0 0.995195 -0.097909 -0 0.980785 -0.19509 -0 0.92388 -0.382684 -0 1 0.000217164 -0 1 0.000217164 -0 1 0.000217164 -0 0.995195 -0.097909 -0 -0.995194 -0.0979183 -0 -0.995194 -0.0979183 -0 -1 0.000198993 -0 -1 0.000198993 -0 -0.92388 -0.382683 -0 -0.92388 -0.382683 -0 -0.995194 -0.0979183 -0 -0.707107 -0.707107 -0 -0.707107 -0.707107 -0 -0.83147 -0.55557 -0 -0.92388 -0.382683 -0 -0.707107 -0.707107 -0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -7.59655e-08 -1 -0 -7.59655e-08 -1 -0 -0.382683 -0.92388 -0 -0.382683 -0.92388 -0 0.382684 -0.92388 -0 0.382684 -0.92388 -0 0.19509 -0.980785 -0 -7.59655e-08 -1 -0 0.707107 -0.707107 -0 0.382684 -0.92388 -0 0.707107 -0.707107 -0 0.92388 -0.382683 -0 0.831469 -0.555571 -0 0.707107 -0.707107 -0 0.995195 -0.097909 -0 0.980785 -0.19509 -0 0.980785 -0.19509 -0 1 0.00021676 -0 1 0.00021676 -0 1 0.00021676 -0 1 0.00021676 -0 -1 0.000231725 -0 -1 0.000231725 -0 -1 0.000231725 -0 -1 0.000231725 -0 -0.995196 -0.0979014 -0 -0.92388 -0.382683 -0 -0.980785 -0.195089 -0 -0.980785 -0.195089 -0 -0.707107 -0.707107 -0 -0.831469 -0.555571 -0 -0.831469 -0.555571 -0 -0.55557 -0.83147 -0 -0.028353 0.999593 0.00329255 -0.028353 0.999593 0.00329255 -0.0312196 0.999513 -0 -0.0312196 0.999513 -0 -0.987897 -0.0350718 0.151097 -0.987897 -0.0350718 0.151097 -0.976176 -0.0699926 0.20538 -0.976176 -0.0699926 0.20538 -1 0 -0 -1 0 -0 -0.022348 -0.999749 0.00163522 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 0 -1 -0 -0.0269333 0.999607 0.00775956 -0.0269333 0.999607 0.00775956 -0.0283763 0.999396 0.0200495 -0.0283763 0.999396 0.0200495 0.129131 -0.991626 0.00156163 0.129131 -0.991626 0.00156163 0.130699 -0.991391 0.00789167 0.130699 -0.991391 0.00789167 0.130699 -0.991391 0.00789167 0 -1 -0 0 -1 -0 -0.0444897 -0.999001 -0.00430708 -0.0442945 -0.999004 -0.00534453 -0.0442945 -0.999004 -0.00534453 -0.0474625 -0.998873 0.000439597 0.129131 -0.991626 0.00156163 0.127557 -0.99182 -0.00476847 0.0639093 -0.997953 -0.00238913 -0.0534036 -0.998524 0.0099329 0 -1 -0 0 -1 -0 0 -1 -0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.382683 -0.92388 -0 -0.382683 -0.92388 -0 -0.19509 -0.980785 -0 -7.59655e-08 -1 -0 -7.59655e-08 -1 -0 -7.59655e-08 -1 -0 0.19509 -0.980785 -0 0.382684 -0.92388 -0 0.555571 -0.831469 -0 0.707107 -0.707107 -0 0.555571 -0.831469 -0 0.92388 -0.382684 -0 0.92388 -0.382684 -0 0.831469 -0.555571 -0 0.92388 -0.382684 -0 0.980785 -0.19509 -0 0.995195 -0.097909 -0 0.995195 -0.097909 -0 0.995195 -0.097909 -0 1 0.000217164 -0 1 0.000217164 -0 1 0.000217164 -0 -0.995194 -0.0979183 -0 -1 0.000198993 -0 -1 0.000198993 -0 -0.995194 -0.0979183 -0 -0.92388 -0.382683 -0 -0.995194 -0.0979183 -0 -0.92388 -0.382683 -0 -0.92388 -0.382683 -0 -0.83147 -0.55557 -0 -0.707107 -0.707107 -0 -0.707107 -0.707107 -0 -0.707107 -0.707107 -0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -7.59655e-08 -1 -0 -0.382683 -0.92388 -0 -0.382683 -0.92388 -0 -7.59655e-08 -1 -0 0.382684 -0.92388 -0 -7.59655e-08 -1 -0 0.19509 -0.980785 -0 0.382684 -0.92388 -0 0.707107 -0.707107 -0 0.707107 -0.707107 -0 0.382684 -0.92388 -0 0.707107 -0.707107 -0 0.831469 -0.555571 -0 0.92388 -0.382683 -0 0.980785 -0.19509 -0 0.980785 -0.19509 -0 0.995195 -0.097909 -0 1 0.00021676 -0 1 0.00021676 -0 1 0.00021676 -0 1 0.00021676 -0 -1 0.000231725 -0 -0.995196 -0.0979014 -0 -1 0.000231725 -0 -1 0.000231725 -0 -1 0.000231725 -0 -0.980785 -0.195089 -0 -0.980785 -0.195089 -0 -0.92388 -0.382683 -0 -0.707107 -0.707107 -0 -0.831469 -0.555571 -0 -0.831469 -0.555571 -0 -0.55557 -0.83147 -0 -0.028353 0.999593 -0.00329255 -0.028353 0.999593 -0.00329255 -0.987897 -0.0350718 -0.151097 -0.976176 -0.0699926 -0.20538 -0.976176 -0.0699926 -0.20538 -0.987897 -0.0350718 -0.151097 -0.022348 -0.999749 -0.00163522 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

3 1 0 5 3 0 1 18 0 0 18 29 0 29 5 3 2 1 1 19 18 18 136 29 20 29 136 23 21 20 20 21 29 23 22 21 29 21 31 29 31 30 161 29 30 161 157 29 157 156 155 157 155 154 154 29 157 154 262 29 29 153 137 29 137 5 262 153 29 153 152 140 153 140 137 140 138 137 138 5 137 5 4 3 138 4 5 3 4 8 8 4 138 140 139 138 142 141 138 142 138 139 8 138 141 163 141 142 163 162 141 8 141 162 8 162 164 8 164 160 24 25 160 24 160 159 160 25 8 26 25 24 8 25 26 24 27 26 8 26 34 24 28 27 24 17 28 13 17 16 13 16 15 15 14 13 24 159 158 158 148 24 149 148 147 147 150 149 147 151 150 8 34 33 3 8 7 33 7 8 7 33 32 3 7 6 7 32 6 3 6 2 12 10 9 127 12 9 127 9 126 12 11 10 129 127 126 129 126 128 256 257 129 256 129 128 143 257 256 143 144 257 146 144 143 146 145 144 35 46 45 35 45 44 35 44 43 35 43 42 35 42 41 35 41 40 35 40 39 35 39 38 35 38 37 37 36 35 47 51 50 47 50 49 49 48 47 80 51 47 80 47 76 54 52 48 54 53 52 57 52 56 57 56 55 60 57 59 60 59 58 60 64 63 60 63 62 62 61 60 61 68 67 67 65 61 67 66 65 77 76 73 73 78 77 69 74 73 73 79 78 72 70 69 69 75 74 72 71 70 81 92 91 81 91 90 81 90 89 81 89 88 81 88 87 81 87 86 81 86 85 81 85 84 81 84 83 83 82 81 96 94 93 97 93 100 96 95 94 122 95 96 122 125 95 119 123 122 121 120 119 121 119 118 119 124 123 114 118 117 114 117 116 116 115 114 97 100 99 99 98 97 103 97 102 103 102 101 106 104 103 106 105 104 109 107 104 109 108 107 107 113 112 107 112 111 111 110 107 133 131 130 135 130 131 133 132 131 135 131 134 261 258 135 261 135 134 261 260 259 261 259 258 165 176 175 165 175 174 165 174 173 165 173 172 165 172 171 165 171 170 165 170 169 165 169 168 165 168 167 167 166 165 177 181 180 177 180 179 179 178 177 177 178 210 177 210 209 184 182 181 184 183 182 187 184 186 187 186 185 190 186 189 190 189 188 189 194 193 189 193 192 192 191 189 197 195 194 197 196 195 203 209 208 205 199 203 203 208 207 207 206 203 205 204 199 202 200 199 202 201 200 211 222 221 211 221 220 211 220 219 211 219 218 211 218 217 211 217 216 211 216 215 211 215 214 211 214 213 213 212 211 226 224 223 228 223 227 226 225 224 225 252 224 225 255 252 254 251 252 254 253 251 251 250 249 251 249 245 246 245 244 244 247 246 244 248 247 227 230 229 227 229 228 233 227 232 233 232 231 236 234 232 236 235 234 239 237 236 239 238 237 239 243 242 239 242 241 241 240 239

+
+
+
+ + + + 1.9426 1.12941 0.56232 1.96816 1.14006 -0 1.95112 0.986698 -0 1.91917 0.980308 0.56232 -1.22577 0.998413 0.61131 -1.26305 0.995218 0.50481 -0.338626 1.36584 0.44091 -0.332236 1.36371 0.522915 1.86828 1.20094 -0 1.83114 1.18694 0.556371 1.25432 1.36468 0.532435 1.25678 1.39296 -0 0.0809844 0.996173 0.75189 -0.334366 0.959008 0.75828 -0.327476 1.27442 0.612271 0.073831 1.35406 0.598098 -0.69767 0.927629 0.76394 -0.670906 1.1358 0.667356 0.227954 1.36158 0.595693 0.158954 1.00015 0.750299 0.316411 1.00818 0.747084 0.342974 1.3701 0.592918 0.761847 1.35222 0.602606 0.776826 1.03165 0.737687 0.939374 1.32324 0.61634 0.990494 1.2423 0.655645 0.984991 1.04967 0.73648 -0.65543 0.925765 0.856467 -0.65543 1.008 0.856467 -0.712602 1.008 0.771707 -0.702513 0.92896 0.786225 -0.703578 1.07616 0.781965 -0.65543 1.07616 0.856467 -0.591112 0.947065 0.951823 -0.586348 1.008 0.958887 -0.591112 1.05912 0.951823 -1.32256 0.995218 -0 -0.359926 1.37436 -0 -0.346882 1.36914 0.27 -1.3048 0.995218 0.27 1.9426 1.12941 -0.56232 1.91917 0.980308 -0.56232 -1.22577 0.998413 -0.61131 -0.332236 1.36371 -0.522915 -0.338626 1.36584 -0.44091 -1.26305 0.995218 -0.50481 1.25432 1.36468 -0.532435 1.83114 1.18694 -0.556371 0.0809844 0.996173 -0.75189 0.073831 1.35406 -0.598098 -0.327476 1.27442 -0.612271 -0.334366 0.959008 -0.75828 -0.670906 1.1358 -0.667356 -0.69767 0.927629 -0.76394 0.158954 1.00015 -0.750299 0.227954 1.36158 -0.595693 0.316411 1.00818 -0.747084 0.776826 1.03165 -0.737687 0.761847 1.35222 -0.602606 0.342974 1.3701 -0.592918 0.984991 1.04967 -0.73648 0.990494 1.2423 -0.655645 0.939374 1.32324 -0.61634 -0.65543 0.925765 -0.856467 -0.702513 0.92896 -0.786225 -0.712602 1.008 -0.771707 -0.65543 1.008 -0.856467 -0.703578 1.07616 -0.781965 -0.65543 1.07616 -0.856467 -0.586348 1.008 -0.958887 -0.591112 0.947065 -0.951823 -0.591112 1.05912 -0.951823 -1.3048 0.995218 -0.27 -0.346882 1.36914 -0.27 + + + + + + + + + + 0.987009 -0.155101 0.0419263 0.987877 -0.155238 -0 0.987877 -0.155238 -0 0.987009 -0.155101 0.0419263 -0.367901 0.924359 0.101035 -0.36545 0.927142 0.0827921 -0.36545 0.927142 0.0827921 -0.367901 0.924359 0.101035 0.299598 0.954066 -0 0.299308 0.953144 0.043954 0.299308 0.953144 0.043954 0.299598 0.954066 -0 -0.0130371 0.39456 0.918778 -0.0216678 0.407417 0.912985 -0.0216678 0.407417 0.912985 -0.0130371 0.39456 0.918778 -0.0221778 0.420384 0.907075 -0.0221778 0.420384 0.907075 -0.00491981 0.394726 0.918786 -0.00491981 0.394726 0.918786 -0.00120842 0.39197 0.919977 -0.00120842 0.39197 0.919977 -0.0146871 0.389542 0.920892 -0.0146871 0.389542 0.920892 -0.028163 0.38704 0.921633 -0.028163 0.38704 0.921633 -0.028163 0.38704 0.921633 0.82985 0 -0.557987 0.832158 -0.00737492 -0.55449 0.835207 -0.0147503 -0.549738 0.830661 0 -0.556779 0.839513 -0.0294963 -0.542539 0.834406 -0.0147504 -0.550952 0.829037 0 -0.559193 0.829037 0 -0.559193 0.829037 0 -0.559193 -0.366459 0.930434 -0 -0.366459 0.930434 -0 -0.364687 0.930075 0.0443179 -0.364687 0.930075 0.0443179 0.987009 -0.155101 -0.0419263 0.987009 -0.155101 -0.0419263 -0.367901 0.924359 -0.101035 -0.367901 0.924359 -0.101035 -0.36545 0.927142 -0.0827921 -0.36545 0.927142 -0.0827921 0.299308 0.953144 -0.043954 0.299308 0.953144 -0.043954 -0.0130371 0.39456 -0.918778 -0.0130371 0.39456 -0.918778 -0.0216678 0.407417 -0.912985 -0.0216678 0.407417 -0.912985 -0.0221778 0.420384 -0.907075 -0.0221778 0.420384 -0.907075 -0.00491981 0.394726 -0.918786 -0.00491981 0.394726 -0.918786 -0.00120842 0.39197 -0.919977 -0.0146871 0.389542 -0.920892 -0.0146871 0.389542 -0.920892 -0.00120842 0.39197 -0.919977 -0.028163 0.38704 -0.921633 -0.028163 0.38704 -0.921633 -0.028163 0.38704 -0.921633 0.82985 0 0.557987 0.830661 0 0.556779 0.835207 -0.0147503 0.549738 0.832158 -0.00737492 0.55449 0.839513 -0.0294963 0.542539 0.834406 -0.0147504 0.550952 0.829037 0 0.559193 0.829037 0 0.559193 0.829037 0 0.559193 -0.364687 0.930075 -0.0443179 -0.364687 0.930075 -0.0443179 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

3 1 0 3 2 1 1 2 41 1 41 40 7 5 4 7 6 5 5 6 38 5 38 39 39 38 37 39 37 36 37 73 72 37 72 36 73 44 45 73 45 72 45 44 43 45 43 42 11 9 8 47 11 8 11 10 9 47 46 11 15 13 12 12 19 18 12 18 15 15 14 13 14 16 13 14 17 16 23 21 20 23 22 21 23 26 25 23 25 24 24 22 23 30 28 27 28 33 27 30 29 28 32 28 29 28 34 33 35 34 28 35 28 32 32 29 31 51 49 48 55 54 48 55 48 49 51 50 49 53 50 51 53 52 50 59 57 56 59 58 57 57 58 62 57 62 61 61 60 57 66 64 63 70 66 63 66 65 64 65 66 68 65 68 67 66 71 68 70 69 66 66 69 71

+
+
+
+
+ + + + 1 0 -0 -0 0 1 -0 -0 -0 -0 1 0 0 0 -0 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/ui/oculus/ofw/src/main.cpp b/ui/oculus/ofw/src/main.cpp new file mode 100644 index 00000000000..d802524f9d2 --- /dev/null +++ b/ui/oculus/ofw/src/main.cpp @@ -0,0 +1,20 @@ +#include "testApp.h" + +//-------------------------------------------------------------- +int main(){ + // set width, height, mode (OF_WINDOW or OF_FULLSCREEN) + ofSetupOpenGL(960*2, 1080, OF_WINDOW); + + testApp *tA = new testApp(); + + pthread_t udp_t; + pthread_create(&udp_t, NULL, udpThread, (void *) &tA->udp); + pthread_t pcd_t; + pthread_create(&pcd_t, NULL, pcdThread,(void *) &tA->pm); + + ofRunApp(tA); // start the app + + pthread_cancel(udp_t); + pthread_cancel(pcd_t); + +} diff --git a/ui/oculus/ofw/src/pointcloud_map.cpp b/ui/oculus/ofw/src/pointcloud_map.cpp new file mode 100644 index 00000000000..1d45a3f2604 --- /dev/null +++ b/ui/oculus/ofw/src/pointcloud_map.cpp @@ -0,0 +1,294 @@ +#include "pointcloud_map.h" + +void PointcloudMap::searcharea(){ + + char fpath[sizeof(PCD_DIR)+sizeof("/Laserxxxxxx_yyyyyy.pcd")]; + + while(max_x==0||max_y==0){usleep(100);} + int prev_x = x - 2; + int prev_y = y - 2; + int center_x = 1; + int center_y = 1; + // we're going to load a ton of points into an ofMesh + for(int i=0;i<9;i++)mesh[i].setMode(OF_PRIMITIVE_POINTS); + printf("%s %06d %06d \n",PCD_DIR,prev_x, prev_y); + sleep(5); + + sload(); + + while(1){ + if((int)x - prev_x == 1){ + printf("----------------------------------\n"); + printf("[%d] x++\n",(int)x); + prev_x = x; + for(int i = 0; i <= 2; i++){ + sprintf(fpath,"%s/Laser%06d_%06d.pcd", PCD_DIR , (int)prev_x+1, (int)prev_y+i-1); + printf("%s ",fpath); + if(ofFile::doesFileExist(fpath)){ + printf("exist.\n Load: mesh[%d]\n",(center_x+2)%3+((center_y+i+2)%3)*3); + load(fpath,(center_x+2)%3+((center_y+i+2)%3)*3); + }else { + printf("\n Clear: mesh[%d]\n",(center_x+2)%3+((center_y+i+2)%3)*3); + mesh[(center_x+2)%3+((center_y+i+2)%3)*3].clear(); + } + } + center_x = (center_x + 1) % 3; + } + if((int)x - prev_x == -1){ + printf("----------------------------------\n"); + printf("[%d] x--\n",(int)x); + prev_x = x; + for(int i = 0; i <= 2; i++){ + sprintf(fpath,"%s/Laser%06d_%06d.pcd", PCD_DIR , prev_x-1, prev_y+i-1); + printf("%s ",fpath); + if(ofFile::doesFileExist(fpath)){ + printf("exist.\n Load: mesh[%d]\n",(center_x+1)%3+((center_y+i+2)%3)*3); + load(fpath,(center_x+1)%3+((center_y+i+2)%3)*3); + }else { + printf("\n Clear: mesh[%d]\n",(center_x+1)%3+((center_y+i+2)%3)*3); + mesh[(center_x+1)%3+((center_y+i+2)%3)*3].clear(); + } + } + center_x = (center_x + 2) % 3; + } + if((int)y - prev_y == 1){ + printf("----------------------------------\n"); + printf("[%d] y++\n",(int)y); + prev_y = y; + for(int j = 0; j <= 2; j++){ + sprintf(fpath,"%s/Laser%06d_%06d.pcd", PCD_DIR , (int)prev_x+j-1, (int)prev_y+1); + printf("%s ",fpath); + if(ofFile::doesFileExist(fpath)){ + printf("exist.\n Load: mesh[%d]\n",(center_x+j+2)%3+((center_y+2)%3)*3); + load(fpath,(center_x+j+2)%3+((center_y+2)%3)*3); + }else { + printf("\n Clear: mesh[%d]\n",(center_x+j+2)%3+((center_y+2)%3)*3); + mesh[(center_x+j+2)%3+((center_y+2)%3)*3].clear(); + } + } + center_y = (center_y + 1) % 3; + } + if((int)y - prev_y == -1){ + printf("----------------------------------\n"); + printf("[%d] y--\n",(int)y); + prev_y = y; + for(int j = 0; j <= 2; j++){ + sprintf(fpath,"%s/Laser%06d_%06d.pcd", PCD_DIR , (int)prev_x+j-1, (int)prev_y-1); + printf("%s ",fpath); + if(ofFile::doesFileExist(fpath)){ + printf("exist.\n Load: mesh[%d]\n",(center_x+j+2)%3+((center_y+1)%3)*3); + load(fpath,(center_x+j+2)%3+((center_y+1)%3)*3); + }else { + printf("\n Clear: mesh[%d]\n",(center_x+j+2)%3+((center_y+1)%3)*3); + mesh[(center_x+j+2)%3+((center_y+1)%3)*3].clear(); + } + } + center_y = (center_y + 2) % 3; + } + if(abs(x-prev_x)>1||abs(y-prev_y)>1){ + printf("[%d %d]\n",(int)x,(int)y); + prev_x = x; + prev_y = y; + for(int i = 0; i <= 2; i++){ + for(int j = 0; j <= 2; j++){ + sprintf(fpath,"%s/Laser%06d_%06d.pcd", PCD_DIR , (int)prev_x+j-1, (int)prev_y+i-1); + printf("%s ",fpath); + + if(ofFile::doesFileExist(fpath)){ + printf("exist.\n Load: mesh[%d]\n",j+i*3); + load(fpath,j+i*3); + }else{ + printf("\n Clear: mesh[%d]\n",j+i*3); + mesh[j+i*3].clear(); + } + } + } + center_x = 1; + center_y = 1; + } + } +} + +void PointcloudMap::load(char* path, int num){ + loading=num; + mesh[num].clear(); + points.clear(); + + totalPoints = 0; + int startPoint = totalPoints; + fin.open(ofToDataPath(path, true).c_str()); + + if(fin.fail()) { + cerr << "File do not exist.\n"; + }else{ + printf("Reading... "); + } + while(getline(fin, line)){ + lines=(ofSplitString(line, " ")); + if(lines.size() == 4){ + float x = ofToFloat(lines[0]); + float y = ofToFloat(lines[1]); + float z = ofToFloat(lines[2]); + float c = ofToFloat(lines[3]); + //printf("%f %f %f %f\n",x,y,z,c); + points.push_back(PCDPoint(x,y,z,c)); + + // Global MINMAX + if(totalPoints == 0){ + printf("update:GlobalPoints\n"); + // max_x = x; min_x = x; max_y = y; min_y = y; max_z = z; min_z = z; + }else{ + // if(x > max_x) max_x = x; + // if(x < min_x) min_x = x; + // if(y > max_y) max_y = y; + // if(y < min_y) min_y = y; + // if(z > max_z) max_z = z; + // if(z < min_z) min_z = z; + } + // Local MINMAX + if(localPoints == 0){ + printf("update:localPoints\n"); + ma_x = x; mi_x = x; ma_y = y; mi_y = y; ma_z = z; mi_z = z; + }else{ + if(x > ma_x) ma_x = x; + if(x < mi_x) mi_x = x; + if(y > ma_y) ma_y = y; + if(y < mi_y) mi_y = y; + if(z > ma_z) ma_z = z; + if(z < mi_z) mi_z = z; + } + + localPoints++; + totalPoints++; + } + } + fin.close(); + + printf("%d\n X [%f : %f]\n Y [%f : %f]\n Z [%f : %f]\n\n", localPoints,mi_x, ma_x, mi_y, ma_y, mi_z, ma_z); + PCDfile file = (PCDfile(num,startPoint,totalPoints,ma_x, ma_y, ma_z, mi_x, mi_y, mi_z, path)); + localPoints = 0; + + + + ofSetVerticalSync(true); + uint8_t r, g, b; + + printf("Creating mesh ... %d to %d\n",file.start,file.end); + for(int j = file.start; j>16; + g = (*(int32_t*)(&points[j].c))>>8 & 0b11111111; + b = (*(int32_t*)(&points[j].c)) & 0b11111111; + mesh[num].addColor(ofFloatColor((double)r/255.0,(double)g/255.0,(double)b/255.0)); +#else + mesh[num].addColor(ofFloatColor(0.2, 1, 0.2, 0.5)); +#endif // COLOR + ofVec3f pos(points[j].x-(min_x+max_x)/2.0, points[j].z, -(points[j].y-(min_y+max_y)/2.0)); + mesh[num].addVertex(pos); + + } + loading=-1; +} + +void PointcloudMap::sload() +{ + string path = STATIC_DIR; + ofDirectory dir(path); + dir.allowExt("pcd"); + dir.listDir(); + readingFileNum = dir.numFiles(); + start.setMode(OF_PRIMITIVE_POINTS); + for(int i = 0; i < readingFileNum; i++){ + int startPoint; + startPoint = totalPoints; + fin.open(ofToDataPath(dir.getPath(i), true).c_str()); + + if(fin.fail()) { + cerr << "File do not exist.\n"; + }else{ + printf("Reading... "); + } + while(getline(fin, line)){ + lines=(ofSplitString(line, " ")); + if(lines.size() == 4){ + float x = ofToFloat(lines[0]); + float y = ofToFloat(lines[1]); + float z = ofToFloat(lines[2]); + float c = ofToFloat(lines[3]); + points.push_back(PCDPoint(x,y,z,c)); + + // Global MINMAX + if(totalPoints == 0){ + printf("update:GlobalPoints\n"); + // max_x = x; min_x = x; max_y = y; min_y = y; max_z = z; min_z = z; + }else{ + // if(x > max_x) max_x = x; + // if(x < min_x) min_x = x; + // if(y > max_y) max_y = y; + // if(y < min_y) min_y = y; + // if(z > max_z) max_z = z; + // if(z < min_z) min_z = z; + } + // Local MINMAX + if(localPoints == 0){ + printf("update:localPoints\n"); + ma_x = x; mi_x = x; ma_y = y; mi_y = y; ma_z = z; mi_z = z; + }else{ + if(x > ma_x) ma_x = x; + if(x < mi_x) mi_x = x; + if(y > ma_y) ma_y = y; + if(y < mi_y) mi_y = y; + if(z > ma_z) ma_z = z; + if(z < mi_z) mi_z = z; + } + + localPoints++; + totalPoints++; + } + } + fin.close(); + + printf("DONE[ %d / %d] %d\n X [%f : %f] Y [%f : %f] Z [%f : %f]\n\n", i, readingFileNum, localPoints,mi_x, ma_x, mi_y, ma_y, mi_z, ma_z); + files.push_back(PCDfile(i,startPoint,totalPoints,ma_x, ma_y, ma_z, mi_x, mi_y, mi_z, dir.getPath(i))); + localPoints = 0; + } + + printf("TOTAL: %d X [%f : %f] Y [%f : %f] Z [%f : %f]\n",totalPoints, min_x, max_x, min_y, max_y, min_z, max_z); + + ofSetVerticalSync(true); + uint8_t r, g, b; + + // we're going to load a ton of points into an ofMesh + start.setMode(OF_PRIMITIVE_POINTS); + + // loop through the image in the x and y axes + int skip = 1; // load a subset of the points + for(int i = 0; i< readingFileNum; i++){ + printf("Creating mesh ... %d %d to %d\n",i,files[i].start,files[i].end); + for(int j = files[i].start; j>16; + g = (*(int32_t*)(&points[j].c))>>8 & 0b11111111; + b = (*(int32_t*)(&points[j].c)) & 0b11111111; + start.addColor(ofFloatColor((double)r/255.0,(double)g/255.0,(double)b/255.0)); +#else +#ifdef RAINBOW + float level = (11 + 3) / 7.0; + if( - 3 <= points[j].z && points[j].z < level * 1 - 3)start.addColor(ofColor::red); + if(level * 1 - 3 <= points[j].z && points[j].z < level * 2 - 3)start.addColor(ofColor::orange); + if(level * 2 - 3 <= points[j].z && points[j].z < level * 3 - 3)start.addColor(ofColor::yellow); + if(level * 3 - 3 <= points[j].z && points[j].z < level * 4 - 3)start.addColor(ofColor::green); + if(level * 4 - 3 <= points[j].z && points[j].z < level * 5 - 3)start.addColor(ofColor::blue); + if(level * 5 - 3 <= points[j].z && points[j].z < level * 6 - 3)start.addColor(ofColor::navy); + if(level * 6 - 3 <= points[j].z && points[j].z <=level * 7 - 3)start.addColor(ofColor::purple); + +#else + start.addColor(ofFloatColor(0.1, 1.0, 0.1,0.3)); +#endif +#endif + ofVec3f pos(points[j].x-(min_x+max_x)/2.0, points[j].z, -(points[j].y-(min_y+max_y)/2.0)); + start.addVertex(pos); + + } + } +} diff --git a/ui/oculus/ofw/src/pointcloud_map.h b/ui/oculus/ofw/src/pointcloud_map.h new file mode 100644 index 00000000000..68bf4d31cfb --- /dev/null +++ b/ui/oculus/ofw/src/pointcloud_map.h @@ -0,0 +1,86 @@ +#ifndef POINTCLOUD_MAP_H_INCLUDED +#define POINTCLOUD_MAP_H_INCLUDED + +#include "ofMain.h" +#include +#include +#include + +#define PCD_DIR "/data/data_moriyama_0.2/map/pointcloud_map" +#define STATIC_DIR "/data/data_moriyama_0.2/map/global_map" +//#define COLOR + +class PCDPoint{ +public: + float x; + float y; + float z; + float c; + PCDPoint(float x,float y, float z, float c){ + this->x = x; + this->y = y; + this->z = z; + this->c = c; + } +}; + +class PCDfile{ +public: + int id; + int start; + int end; + float max_x; + float max_y; + float max_z; + float min_x; + float min_y; + float min_z; + string name; + + PCDfile(int id, int start, int end,float max_x,float max_y,float max_z,float min_x,float min_y,float min_z, string name){ + this->id = id; + this->start = start; + this->end = end; + this->name = name; + this->max_x = max_x; + this->min_x = min_x; + this->max_y = max_y; + this->min_y = min_y; + this->max_z = max_z; + this->min_z = min_z; + } +}; + +class PointcloudMap{ +public: + vector points; + vector files; + + ifstream fin; + string line; + vector lines, pieces; + int x=0; + int y=0; + float max_x=0; + float min_x=0; + float max_y=0; + float min_y=0; + float max_z; + float min_z; + float ma_x,ma_y,mi_x,mi_y,ma_z,mi_z; + int totalPoints = 0; + int localPoints = 0; + int readingFileNum = 0; + bool f=true; + + void searcharea(); + void load(char* path, int num); + void sload(); + int loading=-1; + + ofVboMesh mesh[9]; + + ofVboMesh start; +}; + +#endif // POINTCLOUD_MAP_H_INCLUDED diff --git a/ui/oculus/ofw/src/testApp.cpp b/ui/oculus/ofw/src/testApp.cpp new file mode 100644 index 00000000000..512159caffe --- /dev/null +++ b/ui/oculus/ofw/src/testApp.cpp @@ -0,0 +1,554 @@ +#include "testApp.h" + +//-------------------------------------------------------------- +void testApp::setup() +{ + ofEnableDepthTest(); + ofEnableAlphaBlending(); + ofEnableSmoothing(); + + while(pm.max_x==0||pm.max_y==0){ + pm.max_x = udp.car_x; + pm.max_y = udp.car_y; + pm.min_x = udp.car_x; + pm.min_y = udp.car_y; + pm.x = udp.car_x < 0 ? udp.car_x / 100.0 - 1 : udp.car_x / 100.0; + pm.y = udp.car_y < 0 ? udp.car_y / 100.0 - 1 : udp.car_y / 100.0; + } + printf("%f %f %d %d\n", pm.max_x, pm.max_y, pm.x, pm.y); + +#ifdef VECTOR + vm.setTF(pm.min_x, pm.max_x, pm.min_y, pm.max_y); + vm.loadAll(VECTOR); + vm.set_all(); +#endif + + vs.setMode(OF_PRIMITIVE_LINES); + + glPointSize(1); // make the points bigger + glHint(GL_POINT_SMOOTH_HINT, GL_NICEST); + glEnable(GL_POINT_SMOOTH); // use circular points instead of square points + glColorMaterial(GL_FRONT,GL_AMBIENT_AND_DIFFUSE); + glShadeModel(GL_SMOOTH); + + float fogColor[4]= {0.1, 0.1, 0.1, 0.3}; + glFogi(GL_FOG_MODE, GL_LINEAR); + glFogfv(GL_FOG_COLOR, fogColor); + glFogf(GL_FOG_DENSITY, 0.35); + glHint(GL_FOG_HINT, GL_NICEST); + glFogf(GL_FOG_START, 50.0); + glFogf(GL_FOG_END, 100.0); + glEnable(GL_FOG); + + ofEnableBlendMode(OF_BLENDMODE_SUBTRACT); + + ofBackground(0); + ofSetVerticalSync( true ); + + showOverlay = false; + predictive = true; + + ofHideCursor(); + + oculusRift.baseCamera = &cam; + oculusRift.setup(); + printf("%f %f\n",(fclip=oculusRift.baseCamera->getFarClip()),oculusRift.baseCamera->getNearClip()); + fclip = 50; + oculusRift.baseCamera->setNearClip(0.1); + oculusRift.baseCamera->setFarClip(fclip); + cam.setNearClip(0.1); + cam.setFarClip(70); + cam1.setNearClip(0.1); + cam1.setFarClip(70); + cam2.setNearClip(0.1); + cam2.setFarClip(70); + cam3.setNearClip(0.1); + cam3.setFarClip(70); + + //enable mouse; + cam.begin(); + cam.end(); + + // JUMP + initial_velocity = 2 * (float)MAX_OFFSET / (float)JUMP_TIME; + accel = initial_velocity / (float)JUMP_TIME; + + // Car Model + model.loadModel("prius_model.dae",true); + model.setScale(0.004, 0.004, 0.004); + + ofToggleFullscreen(); + pm.f=false; + + sun.setDiffuseColor(ofColor::white); + sun.setSpecularColor(ofColor::black); + sun.setDirectional(); + sun.setOrientation(ofVec3f(90,0,45)); + carlight.setDiffuseColor(ofColor::white); + carlight.setSpecularColor(ofColor::black); + carlight.setSpotlight(); +} + +//-------------------------------------------------------------- +void testApp::update() +{ + car.x = udp.car_x - (pm.min_x + pm.max_x) / 2.0; + car.y = (udp.car_y - (pm.min_y + pm.max_y) / 2.0) * (-1); + car.z = udp.car_z; + + pm.x = udp.car_x < 0 ? udp.car_x / 100.0 - 1 : udp.car_x / 100.0; + pm.y = udp.car_y < 0 ? udp.car_y / 100.0 - 1 : udp.car_y / 100.0; + + // Stop vibration + euler.x = (udp.roll < 5) || (udp.roll > -5) ? 0 : udp.roll; + euler.y = udp.yaw - 90; + euler.z = 0; + + // JUMP + if((jump==0 && OculusRPY.x > -100 && OculusRPY.x < -50) || (jump==1 && OculusRPY.x>=-30))count++; + else count = 0; + if(count > 500){ + count = 0; + jump = 1 - jump; + } + fps = ofGetFrameRate(); + if(jump == 1 && offset < MAX_OFFSET){ + offset += velocity / fps; + velocity -= accel / fps; + } + else if(jump == 0 && offset > 0){ + offset -= velocity / fps; + velocity -= accel / fps; + } + if(offset >= MAX_OFFSET){ + offset = MAX_OFFSET; + velocity = initial_velocity; + } + if(offset <= 0){ + offset = 0; + velocity = initial_velocity; + } + cam1.setGlobalPosition(car.x, car.z + offset, car.y); + cam1.setOrientation(euler); + cam2 = cam1; + cam3 = cam1; + cam1.truck(0.3); + cam1.dolly(0.27); + cam1.boom(-0.93); + cam2.dolly(7); + cam2.boom(2); + cam3.boom(-1.8); + cam3.dolly(-1.2); + cam3.truck(-0.9); + cam3.pan(-15); + carlight.setGlobalPosition(car.x, car.z, car.y); + carlight.setOrientation(euler); + carlight.dolly(1); + //Driver's view + switch(mode){ + case 0 : + oculusRift.baseCamera->setGlobalPosition(camPos); + break; + case 1 : + cam = cam1; + break; + case 2 : + cam = cam2; + break; + case 3 : + cam = cam3; + break; + } + if(udp.vscan.size()==vs.getNumVertices()){ + vs.clear(); + for(int i = 0;i < udp.vscan.size(); i++){ + vs.addVertex(ofVec3f(udp.vscan[i].x-(pm.min_x + pm.max_x) / 2.0, udp.vscan[i].z, -(udp.vscan[i].y-(pm.min_y + pm.max_y) / 2.0))); + } + } +} + +//-------------------------------------------------------------- +void testApp::draw() +{ + if(disp){ + if(oculusRift.isSetup()){ + + ofSetColor(100, 100, 250); + glEnable(GL_DEPTH_TEST); + camera = oculusRift.baseCamera->getGlobalPosition(); + OculusQuaternion = oculusRift.getOrientationQuat(); + OculusRPY = OculusQuaternion.getEuler(); + oculusRift.beginLeftEye(); + drawScene(); + oculusRift.endLeftEye(); + + oculusRift.beginRightEye(); + drawScene(); + oculusRift.endRightEye(); + + oculusRift.draw(); + + glDisable(GL_DEPTH_TEST); + ofSetColor(255); + ofDrawBitmapString(ofToString(ofGetFrameRate())+"fps",10,15); + } + else{ + cam.begin(); + + drawScene(); + + cam.end(); + } + }else{ + ofDrawBitmapString(ofToString(ofGetFrameRate())+"fps",10,15); + cam.begin(); + drawScene(); + cam.end(); + } + if(op){ + + ofSetColor(255,255); + ofFill(); + + ofDrawBitmapString("x :\t"+ofToString(udp.car_x),300,100); + ofDrawBitmapString("y :\t"+ofToString(udp.car_y),300,110); + ofDrawBitmapString("z :\t"+ofToString(udp.car_z),300,120); + ofDrawBitmapString("CAM :\t"+ofToString(camPos.x),500,100); + ofDrawBitmapString("CAM :\t"+ofToString(camPos.y),500,110); + ofDrawBitmapString("CAM :\t"+ofToString(camPos.z),500,120); + ofDrawBitmapString("roll :\t"+ofToString(udp.roll),300,150); + ofDrawBitmapString("pitch :\t"+ofToString(udp.pitch),300,160); + ofDrawBitmapString("yaw :\t"+ofToString(udp.yaw),300,170); + ofDrawBitmapString("CAM :\t"+ofToString(oculusRift.baseCamera->getRoll()),500,150); + ofDrawBitmapString("CAM :\t"+ofToString(oculusRift.baseCamera->getPitch()),500,160); + ofDrawBitmapString("CAM :\t"+ofToString(oculusRift.baseCamera->getHeading()),500,170); + ofDrawBitmapString("UNIX :\t"+ofToString(ofGetUnixTime()),300,200); + ofDrawBitmapString("time :\t"+ofToString(ofGetElapsedTimef()),300,210); + } + +} + +//-------------------------------------------------------------- +void testApp::drawScene() +{ +// ofEnableSeparateSpecularLight(); + if(mout){ + ofSetColor(ofColor::silver); +// sun.enable(); + + ofPushMatrix(); + ofTranslate(car.x, car.z-2.0, car.y); + ofRotateX(90); + ofRotateZ(-90-euler.y); + if(fill) model.drawFaces(); + else model.drawWireframe(); + ofPopMatrix(); +// sun.disable(); + } + // Change BackGround Color + ofPushMatrix(); + ofPushStyle(); + ofTranslate(camera); + ofSetColor(ofColor::black); + ofSphere(100); + ofPopStyle(); + ofPopMatrix(); +// carlight.enable(); + pm.start.draw(); + for(int i=0; i < 9; i++) + if(i != pm.loading ) + pm.mesh[i].draw(); + +#ifdef CAR_LOC + ofPushStyle(); + ofNoFill(); + ofSetColor(ofColor::blue); + for(int i = 0;i < udp.oth.size(); i++){ + ofPushMatrix(); + ofTranslate(udp.oth[i].x- (pm.min_x + pm.max_x) / 2.0,udp.car_z-1.5,(udp.oth[i].y - (pm.min_y + pm.max_y) / 2.0) * (-1)); + ofRotateX(90); + ofRotateZ(-90-euler.y); + ofDrawBox(0,0,0,3,1.5,1.5); + ofPopMatrix(); + } + ofSetColor(ofColor::red); + for(int i = 0;i < udp.ped.size(); i++){ + ofPushMatrix(); + ofTranslate(udp.oth[i].x- (pm.min_x + pm.max_x) / 2.0,udp.car_z-1.5,(udp.oth[i].y - (pm.min_y + pm.max_y) / 2.0) * (-1)); +// ofRotateY(); + ofDrawCylinder(0,0,0,0.3,1.5); + ofPopMatrix(); + } + ofSetColor(ofColor::red); + for(int i = 0;i < udp.obj.size(); i++){ + ofDrawBox(udp.obj[i].x- (pm.min_x + pm.max_x) / 2.0,udp.obj[i].z - 1,(udp.obj[i].y - (pm.min_y + pm.max_y) / 2.0) * (-1),1,1,1); + } + ofFill(); + ofPopStyle(); +#endif + vs.draw(); +// udp.vscan.draw(); +#ifdef VECTOR +// vm.draw(); + vm.drawWireframe(); +#endif +// carlight.disable(); +} + +//-------------------------------------------------------------- +void testApp::keyPressed(int key) +{ + switch (key) { + case 'w': + rotAng = (oculusRift.baseCamera->getOrientationEuler()).y; + camPos.x -= sin(rotAng/180.0*PI)*10; + camPos.z -= cos(rotAng/180.0*PI)*10; + break; + case 's': + rotAng = (oculusRift.baseCamera->getOrientationEuler()).y; + camPos.x += sin(rotAng/180.0*PI)*10; + camPos.z += cos(rotAng/180.0*PI)*10; + break; + case 'a': + camPos.z +=10; + break; + case 'd': + camPos.z -=10; + break; + case 'r': + camPos.y +=10; + break; + case 'f': + camPos.y -=10; + break; + + case 'W': + rotAng = (oculusRift.baseCamera->getOrientationEuler()).y; + camPos.x -= sin(rotAng/180.0*PI); + camPos.z -= cos(rotAng/180.0*PI); + break; + case 'S': + rotAng = (oculusRift.baseCamera->getOrientationEuler()).y; + camPos.x += sin(rotAng/180.0*PI); + camPos.z += cos(rotAng/180.0*PI); + break; + case 'A': + camPos.z +=10; + break; + case 'D': + camPos.z -=10; + break; + case 'R': + camPos.y +=10; + break; + case 'F': + camPos.y -=10; + break; + case 'e': + oculusRift.baseCamera->rotate(-10,0,1,0); + break; + case 'q': + oculusRift.baseCamera->rotate(+10,0,1,0); + break; + case 'E': + oculusRift.baseCamera->rotate(-1,0,1,0); + break; + case 'Q': + oculusRift.baseCamera->rotate(+1,0,1,0); + break; + case '0': + ofToggleFullscreen(); + break; + case '1': + mode = 1; + break; + case '2': + mode = 2; + break; + case '3': + mode = 3; + break; + case ' ': + mode = 0; + break; + case 'j': + if(offset == MAX_OFFSET || offset == 0){ + jump = 1 - jump; + } + break; + case 'i': + op = !op; + break; + case '.': + udp.pose = !udp.pose; + break; + case 'm': + mout = !mout; + break; + case 'n': + fill = !fill; + break; + case '@': + disp = !disp; + break; + default: + break; + } + +} + +//-------------------------------------------------------------- +void testApp::keyReleased(int key) +{ + +} + +//-------------------------------------------------------------- +void testApp::mouseMoved(int x, int y) +{ + // cursor2D.set(x, y, cursor2D.z); +} + +//-------------------------------------------------------------- +void testApp::mouseDragged(int x, int y, int button) +{ + // cursor2D.set(x, y, cursor2D.z); +} + +//-------------------------------------------------------------- +void testApp::mousePressed(int x, int y, int button) +{ + +} + +//-------------------------------------------------------------- +void testApp::mouseReleased(int x, int y, int button) +{ + +} + +//-------------------------------------------------------------- +void testApp::windowResized(int w, int h) +{ + +} + +//-------------------------------------------------------------- +void testApp::gotMessage(ofMessage msg) +{ + +} + +//-------------------------------------------------------------- +void testApp::dragEvent(ofDragInfo dragInfo) +{ + +} + +int basetime = 0; + +void *udpThread(void *arg) +{ + udparg *n; + n = (udparg *)arg; + char buf[BUFSIZE]; + float tm; +#ifdef LOCAL + std::ifstream fs(LOCAL); + if (fs.fail()) { + cerr << "Log File do not exist."; + exit(1); + } + n->pose=false; + + while(1){ + while(fs.getline(buf, BUFSIZE)){ + while(n->pose){usleep(100);} + string message = buf; + if(message != ""){ + vector udp = ofSplitString(message, " "); + if(udp.size() == 9){ + if(strcmp(udp[1].c_str(),"CAR")==0){ + n->car_x = atof(udp[3].c_str()); + n->car_y = atof(udp[4].c_str()); + n->car_z = atof(udp[5].c_str()); + n->roll = atof(udp[6].c_str()); + n->pitch = atof(udp[7].c_str()); + n->yaw = atof(udp[8].c_str()); + } + if(strcmp(udp[1].c_str(),"OTH")==0){ + n->oth.push_back(ofVec3f(atof(udp[3].c_str()),atof(udp[4].c_str()),atof(udp[5].c_str()))); + } + } + if(basetime == 0)basetime = string2unixtime(udp[0].c_str()); + // while((float)(string2unixtime(udp[0].c_str()) - basetime) / 1000.0 >= ofGetElapsedTimef()){ + // } + usleep(80009); + n->oth.clear(); + } + } + fs.clear(); + fs.seekg(0, ios_base::beg); + } +#else + //UDPReceiver + ofxUDPManager udpNDT; + udpNDT.Create(); + udpNDT.Bind(PORT); + udpNDT.SetNonBlocking(true); + + while(1){ + udpNDT.Receive(buf, BUFSIZE); + string message = buf; + if(message != ""){ + vector udp = ofSplitString(message, " "); + if(udp.size() == 9){ + if(strcmp(udp[1].c_str(),"CAR")==0){ + n->car_x = atof(udp[3].c_str()); + n->car_y = atof(udp[4].c_str()); + n->car_z = atof(udp[5].c_str()); + n->roll = atof(udp[6].c_str()); + n->pitch = atof(udp[7].c_str()); + n->yaw = atof(udp[8].c_str()); + } + else if(strcmp(udp[1].c_str(),"OTH")==0){ + n->oth.push_back(ofVec3f(atof(udp[3].c_str()),atof(udp[4].c_str()),atof(udp[5].c_str()))); + } + else if(strcmp(udp[1].c_str(),"PED")==0){ + n->ped.push_back(ofVec3f(atof(udp[3].c_str()),atof(udp[4].c_str()),atof(udp[5].c_str()))); + } + else if(strcmp(udp[1].c_str(),"OBJ")==0){ + n->obj.push_back(ofVec3f(atof(udp[3].c_str()),atof(udp[4].c_str()),atof(udp[5].c_str()))); + } + else if(strcmp(udp[1].c_str(),"VSC")==0){ + n->vscan.push_back(ofVec3f(atof(udp[3].c_str()),atof(udp[4].c_str()),atof(udp[5].c_str()))); + n->vscan.push_back(ofVec3f(atof(udp[6].c_str()),atof(udp[7].c_str()),atof(udp[8].c_str()))); + } + } + if(ofGetElapsedTimef() - tm > 0.5){ + tm = ofGetElapsedTimef(); + n->oth.clear(); + n->ped.clear(); + n->obj.clear(); + n->vscan.clear(); + } + } + } +#endif +} + +void *pcdThread(void *arg) +{ + PointcloudMap *p = reinterpret_cast(arg); + p->searcharea(); +} + + +int string2unixtime(string str){ + int rec=0; + for(int i = 0; i < 13; i++){ + rec *= 10; + rec += str[i] - '0'; + } + return rec; +} diff --git a/ui/oculus/ofw/src/testApp.h b/ui/oculus/ofw/src/testApp.h new file mode 100644 index 00000000000..b385918c3cf --- /dev/null +++ b/ui/oculus/ofw/src/testApp.h @@ -0,0 +1,145 @@ +#pragma once + +#include "ofMain.h" +#include "pointcloud_map.h" +#include "ofxNetwork.h" +#include "ofxOculusDK2.h" +#include "vector_map.h" +#include "ofxAssimpModelLoader.h" + + +#define BUFSIZE 100000 +#define PORT 59630 + +#define MAX_OFFSET 20 +#define JUMP_TIME 2 + +//#define LOCAL "/data/log/moriyama_150630/udp.txt" // Run without data transmission +//#define COLOR // Enable PCD map color +#define VECTOR "/data/data_moriyama_0.2/map/vector_map" // Draw vector_map +#define CAR_LOC // Draw other car + +typedef struct{ + ofColor color; + ofVec3f pos; + ofVec3f floatPos; + float radius; + bool bMouseOver; + bool bGazeOver; +} DemoSphere; + + +typedef struct{ + float car_x; + float car_y; + float car_z; + float roll; + float pitch; + float yaw; + bool pose = true; + vector vscan; + vector oth; + vector ped; + vector obj; +} udparg; + +class testApp : public ofBaseApp +{ + public: + + void setup(); + void setPointCloudMap(); + void update(); + void draw(); + + void drawScene(); + + void keyPressed(int key); + void keyReleased(int key); + void mouseMoved(int x, int y); + void mouseDragged(int x, int y, int button); + void mousePressed(int x, int y, int button); + void mouseReleased(int x, int y, int button); + void windowResized(int w, int h); + void dragEvent(ofDragInfo dragInfo); + void gotMessage(ofMessage msg); + + ofxOculusDK2 oculusRift; + + ofLight light; + ofCamera cam; + bool showOverlay; + bool predictive; + vector demos; + + ofVec3f cursor2D; + ofVec3f cursor3D; + + ofVec3f cursorRift; + ofVec3f demoRift; + + ofVec3f cursorGaze; + + vector points; + vector file; + + float max_x; + float min_x; + float max_y; + float min_y; + float max_z; + float min_z; + float ma_x,ma_y,mi_x,mi_y,ma_z,mi_z; + int totalPoints = 0; + int localPoints = 0; + int readingFileNum = 0; + + ofVec3f camPos; + ofVec3f car; + ofVec3f euler; + + float rotAng = 0; + float fc = 0.0; + float fclip; + ifstream fin; + string line; + vector lines, pieces; + + ofVboMesh mesh; + ofVboMesh vs; + + ofCamera cam1,cam2,cam3; + + // Argument for udpThread + udparg udp; + + int mode = 1; + + // For JUMP + int count=0; + int jump = 0; + float offset = 0; + float accel = 0; + float velocity = 0; + float initial_velocity = 0; + float fps = 0; + ofVec3f camera,OculusRPY; + ofQuaternion OculusQuaternion; + + PointcloudMap pm; + VectorMap vm; + + ofLight carlight; + ofxAssimpModelLoader model; + bool op = false; + bool disp = true; + bool mout = true; + bool fill = false; + + ofLight sun; +}; + +int string2unixtime(string str); + +void* pcdThread(void *); +void* udpThread(void *); diff --git a/ui/oculus/ofw/src/vector_map.cpp b/ui/oculus/ofw/src/vector_map.cpp new file mode 100644 index 00000000000..cbe968936b1 --- /dev/null +++ b/ui/oculus/ofw/src/vector_map.cpp @@ -0,0 +1,911 @@ +// +// vector_map.cpp +// ORR_PointCloud +// +// Created by Kenjiro on 6/6/15. +// +// + +#include "vector_map.h" + +typedef std::vector > File_contents; + +static inline File_contents read_csv(const char* filename){ + File_contents fileContents; + fileContents.clear(); + + std::ifstream ifs(filename); + if (ifs == 0){ + ifs.close(); + return fileContents; + } + std::string line_contents; + std::getline(ifs, line_contents); // skip first header line + + while (std::getline(ifs, line_contents)) + { + std::istringstream ss(line_contents); + + std::vector column; + std::string element; + while (std::getline(ss, element, ',')) { + column.push_back(element); + } + fileContents.push_back(column); + } + ifs.close(); + return fileContents; +} + +int VectorMap::read_roadedge(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_gutter(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_curb(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_whiteline(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_stopline(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_zebrazone(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_crosswalk(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_roadsurfacemark(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_poledata(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_roadsign(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_s.id, tmp_s) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_signaldata(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_s.id, tmp_s) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_streetlight(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_utilitypole(const char* filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.id, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_pointclass(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_p.pid, tmp_p) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_vectorclass(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_v.vid, tmp_v) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_lineclass(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.lid, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_areaclass(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.aid, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_poleclass(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.plid, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_boxclass(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.bid, tmp_l) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_dtlane(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_a.did, tmp_a) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_nodedata(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_a.nid, tmp_a) ); + } + + return EXIT_SUCCESS; +} +int VectorMap::read_lanedata(const char *filename){ + File_contents fileContents = read_csv(filename); + if (fileContents.empty()) + return EXIT_FAILURE; + + size_t line_num = fileContents.size(); + for (int i=0; i::value_type(tmp_l.lnid, tmp_l) ); + } + + return EXIT_SUCCESS; +} + +void VectorMap::loadAll (const std::string &dirname) +{ + string rename = dirname + "/roadedge.csv"; + if (read_roadedge((char*)rename.c_str()) == EXIT_FAILURE) { + std::cerr << rename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << rename << "\t load complete." << std::endl; + + string guttername = dirname + "/gutter.csv"; + if (read_gutter((char*)guttername.c_str()) == EXIT_FAILURE) { + std::cerr << guttername << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << guttername << "\t load complete." << std::endl; + + string curbname = dirname + "/curb.csv"; + if (read_curb((char*)curbname.c_str()) == EXIT_FAILURE) { + std::cerr << curbname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << curbname << "\t load complete." << std::endl; + + //string clinename = dirname + "/cline.csv"; + string clinename = dirname + "/whiteline.csv"; + if (read_whiteline ((char*)clinename.c_str()) == EXIT_FAILURE) { + std::cerr << clinename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << clinename << "\t load complete." << std::endl; + + string slinename = dirname + "/stopline.csv"; + if (read_stopline ((char*)slinename.c_str()) == EXIT_FAILURE) { + std::cerr << slinename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << slinename << "\t load complete." << std::endl; + + string zebraname = dirname + "/zebrazone.csv"; + if (read_zebrazone ((char*)zebraname.c_str()) == EXIT_FAILURE) { + std::cerr << zebraname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << zebraname << "\t load complete." << std::endl; + + string crossname = dirname + "/crosswalk.csv"; + if (read_crosswalk ((char*)crossname.c_str()) == EXIT_FAILURE) { + std::cerr << crossname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << crossname << "\t load complete." << std::endl; + + string roadsurfname = dirname + "/road_surface_mark.csv"; + if (read_roadsurfacemark ((char*)roadsurfname.c_str()) == EXIT_FAILURE) { + std::cerr << roadsurfname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << roadsurfname << "\t load complete." << std::endl; + + string poledataname = dirname + "/poledata.csv"; + if (read_poledata ((char*)poledataname.c_str()) == EXIT_FAILURE) { + std::cerr << poledataname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << poledataname << "\t load complete." << std::endl; + + string roadsignname = dirname + "/roadsign.csv"; + if (read_roadsign ((char*)roadsignname.c_str()) == EXIT_FAILURE) { + std::cerr << roadsignname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << roadsignname << "\t load complete." << std::endl; + + //string signalname = dirname + "/signal.csv"; + string signalname = dirname + "/signaldata.csv"; + if (read_signaldata ((char*)signalname.c_str()) == EXIT_FAILURE) { + std::cerr << signalname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << signalname << "\t load complete." << std::endl; + + string lightname = dirname + "/streetlight.csv"; + if (read_streetlight ((char*)lightname.c_str()) == EXIT_FAILURE) { + std::cerr << lightname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << lightname << "\t load complete." << std::endl; + + string utilitypolename = dirname + "/utilitypole.csv"; + if (read_utilitypole ((char*)utilitypolename.c_str()) == EXIT_FAILURE) { + std::cerr << utilitypolename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << utilitypolename << "\t load complete." << std::endl; + + + string ptname = dirname + "/point.csv"; + if (read_pointclass((char*)ptname.c_str()) == EXIT_FAILURE) { + std::cerr << ptname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << ptname << "\t load complete." << std::endl; + + string vectorname = dirname + "/vector.csv"; + if (read_vectorclass ((char*)vectorname.c_str()) == EXIT_FAILURE) { + std::cerr << vectorname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << vectorname << "\t load complete." << std::endl; + + string linename = dirname + "/line.csv"; + if (read_lineclass((char*)linename.c_str()) == EXIT_FAILURE) { + std::cerr << linename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << linename << "\t load complete." << std::endl; + + string areaname = dirname + "/area.csv"; + if (read_areaclass ((char*)areaname.c_str()) == EXIT_FAILURE) { + std::cerr << areaname << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << areaname << "\t load complete." << std::endl; + + string polename = dirname + "/pole.csv"; + if (read_poleclass ((char*)polename.c_str()) == EXIT_FAILURE) { + std::cerr << polename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << polename << "\t load complete." << std::endl; + +// string boxname = dirname + "/box.csv"; +// if (read_boxclass ((char*)boxname.c_str()) == EXIT_FAILURE) { +// std::cerr << boxname << "\t load fail." << std::endl; +// exit(EXIT_FAILURE); +// } +// std::cout << boxname << "\t load complete." << std::endl; + + + string dtlanename = dirname + "/dtlane.csv"; + if (read_dtlane((char*)dtlanename.c_str()) == EXIT_FAILURE) { + std::cerr << dtlanename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << dtlanename << "\t load complete." << std::endl; + + string nodename = dirname + "/node.csv"; + if (read_vectorclass ((char*)vectorname.c_str()) == EXIT_FAILURE) { + std::cerr << nodename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << nodename << "\t load complete." << std::endl; + + + string lanename = dirname + "/lane.csv"; + if (read_lanedata ((char*)lanename.c_str()) == EXIT_FAILURE) { + std::cerr << lanename << "\t load fail." << std::endl; + exit(EXIT_FAILURE); + } + std::cout << lanename << "\t load complete." << std::endl; + + + std::cout << "all vecter maps loaded." << std::endl; + +} + +ofPoint VectorMap::get_point(int pid){ + ofPoint point; + point.x = points[pid].bx - (min_x + max_x) / 2.0; // b or bx? + point.z = (points[pid].ly - (min_y + max_y) / 2.0) * (-1); // l or ly? + point.y = points[pid].h; // Y-up or Z-up? + + return point; +} + +int VectorMap::set_roadedge(){ + for(int i =0;i < roadedges.size();i++){ + if (roadedges[i].id <= 0) continue; + int lid = roadedges[i].lid; + if(lines[lid].blid == 0) { + re_mesh.push_back(set_lineclass(OF_PRIMITIVE_LINE_STRIP, ofColor::white, 3, lid)); + } + } + roadedges.clear(); + return EXIT_SUCCESS; + +} +int VectorMap::set_gutter(){ + for(int i =0;i < gutters.size();i++){ + if (gutters[i].id <= 0) continue; + int aid = gutters[i].aid; + gutter_mesh.push_back(set_areaclass(OF_PRIMITIVE_LINE_STRIP, ofColor::gray, aid)); + } + gutters.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_curb(){ + for(int i =0;i < curbs.size();i++){ + if (curbs[i].id <= 0) continue; + int lid = curbs[i].lid; + if(lines[lid].blid == 0) { + curb_mesh.push_back(set_lineclass(OF_PRIMITIVE_LINE_STRIP, ofColor::white, 3, lid)); + } + } + curbs.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_whiteline(){ + for(int i =0;i < whitelines.size();i++){ + if (whitelines[i].id <= 0) continue; + int lid = whitelines[i].lid; + if(lines[lid].blid == 0) { + if(whitelines[i].color == 'W')wline_mesh.push_back(set_lineclass(OF_PRIMITIVE_LINE_STRIP, ofColor::white, 3, lid)); + if(whitelines[i].color == 'Y')wline_mesh.push_back(set_lineclass(OF_PRIMITIVE_LINE_STRIP, ofFloatColor(1.0, 0.5, 0.0), 3, lid)); + } + } + whitelines.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_stopline(){ + for(int i =0;i < stoplines.size();i++){ + if (stoplines[i].id <= 0) continue; + int lid = stoplines[i].lid; + if(lines[lid].blid == 0) { + sline_mesh.push_back(set_lineclass(OF_PRIMITIVE_LINE_STRIP, ofColor::white, 3, lid)); + } + } + stoplines.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_zebrazone(){ + for(int i =0;i < zebrazones.size();i++){ + if (zebrazones[i].id <= 0) continue; + int aid = zebrazones[i].aid; + zz_mesh.push_back(set_areaclass(OF_PRIMITIVE_LINE_LOOP, ofColor::white, aid)); + } + zebrazones.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_crosswalk(){ + for(int i =0;i < crosswalks.size();i++){ + if (crosswalks[i].id <= 0) continue; + int aid = crosswalks[i].aid; + cw_mesh.push_back(set_areaclass(OF_PRIMITIVE_LINE_LOOP, ofColor::white, aid)); + } + crosswalks.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_roadsurfacemark(){ + for(int i =0;i < roadsurfacemarks.size();i++){ + if (roadsurfacemarks[i].id <= 0) continue; + int aid = roadsurfacemarks[i].aid; + rsm_mesh.push_back(set_areaclass(OF_PRIMITIVE_LINE_LOOP, ofColor::white, aid)); + } + roadsurfacemarks.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_poledata(){ + for(int i =0;i < poledatas.size();i++){ + if (poledatas[i].id <= 0) continue; + int plid = poledatas[i].plid; + pd_mesh.push_back(set_poleclass(ofColor::gray, plid)); + } + poledatas.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_roadsign(){ + for(int i =0;i < roadsigns.size();i++){ + if (roadsigns[i].id <= 0) continue; + int plid = roadsigns[i].plid; + rs_mesh.push_back(set_poleclass(ofColor::white, plid)); + } + roadsigns.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_signaldata(){ + for(int i =0;i < signaldatas.size();i++){ + if (signaldatas[i].id <= 0) continue; + int plid = signaldatas[i].plid; + sd_mesh.push_back(set_poleclass(ofColor::gray, plid)); + } + signaldatas.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_streetlight(){ + for(int i =0;i < streetlights.size();i++){ + if (streetlights[i].id <= 0) continue; + int lid = streetlights[i].lid; + int plid = streetlights[i].plid; + sl_line_mesh.push_back(set_lineclass(OF_PRIMITIVE_LINE_LOOP, ofColor::yellow, 3, lid)); + sl_pole_mesh.push_back(set_poleclass(ofColor::gray, plid)); + } + streetlights.clear(); + return EXIT_SUCCESS; +} +int VectorMap::set_utilitypole(){ + for(int i =0;i < utilitypoles.size();i++){ + if (utilitypoles[i].id <= 0) continue; + int plid = utilitypoles[i].plid; + up_mesh.push_back(set_poleclass(ofColor::gray, plid)); + } + utilitypoles.clear(); + return EXIT_SUCCESS; +} + +//int VectorMap::draw_pointclass(){} +//int VectorMap::draw_vectorclass(){} +ofVboMesh VectorMap::set_lineclass(ofPrimitiveMode mode, ofColor color, float width, int lineid){ + int lid = lineid; + ofVboMesh tmp; + ofVec3f pos; + tmp.setMode(mode); + pos.set(get_point(lines[lid].bpid)); + tmp.addVertex(pos); + tmp.addColor(color); + if(lines[lid].flid==0){ + pos.set(get_point(lines[lid].fpid)); + tmp.addVertex(pos); + tmp.addColor(color); + } + while(lines[lid].flid!=0){ + pos.set(get_point(lines[lid].fpid)); + tmp.addVertex(pos); + tmp.addColor(color); + lid = lines[lid].flid; + } + return tmp; +} +ofVboMesh VectorMap::set_areaclass(ofPrimitiveMode mode, ofColor color, int aid){ + int lid = areas[aid].slid; + ofVboMesh tmp; + ofVec3f pos; + tmp.setMode(mode); + pos.set(get_point(lines[lid].bpid)); + tmp.addVertex(pos); + tmp.addColor(color); + while(lid != areas[aid].elid){ + pos.set(get_point(lines[lid].fpid)); + tmp.addVertex(pos); + tmp.addColor(color); + lid = lines[lid].flid; + } + return tmp; +} +ofVboMesh VectorMap::set_poleclass(ofColor color, int plid){ + int vid = poles[plid].vid; + ofVboMesh tmp = ofVboMesh::cylinder(poles[plid].dim/2.0, poles[plid].length); + ofVec3f point; + ofVec3f pos = get_point(vectors[vid].pid); + +// RotateX 90 + for(int i = 0; i < tmp.getNumVertices(); i++){ + point = tmp.getVertex(i); + tmp.setVertex(i, ofVec3f(point.x, point.y + poles[plid].length / 2.0, point.z)); + } + + for(int i = 0; i < tmp.getNumVertices(); i++){ + point = tmp.getVertex(i); + point += pos; + tmp.setVertex(i, point); + tmp.addColor(color); + } + return tmp; + } +//int VectorMap::draw_boxclass(){} + +//int VectorMap::draw_dtlane(){} +//int VectorMap::draw_nodedata(){} +//int VectorMap::draw_lanedata(){} + +void VectorMap::set_all (){ + set_roadedge(); + set_gutter(); + set_curb(); + set_whiteline(); + set_stopline(); + set_zebrazone(); + set_crosswalk(); + set_roadsurfacemark(); + set_poledata(); + set_roadsign(); + set_signaldata(); + set_streetlight(); + set_utilitypole(); +} + + +void VectorMap::draw (){ + glDisable(GL_DEPTH_TEST); + for(int i = 0; i < re_mesh.size(); i++) re_mesh[i].draw(); + for(int i = 0; i < gutter_mesh.size(); i++) gutter_mesh[i].draw(); + for(int i = 0; i < curb_mesh.size(); i++) curb_mesh[i].draw(); + for(int i = 0; i < wline_mesh.size(); i++) wline_mesh[i].draw(); + for(int i = 0; i < sline_mesh.size(); i++) sline_mesh[i].draw(); + for(int i = 0; i < zz_mesh.size(); i++) zz_mesh[i].draw(); + for(int i = 0; i < cw_mesh.size(); i++) cw_mesh[i].draw(); + for(int i = 0; i < rsm_mesh.size(); i++) rsm_mesh[i].draw(); + glEnable(GL_DEPTH_TEST); + for(int i = 0; i < pd_mesh.size(); i++) pd_mesh[i].draw(); + for(int i = 0; i < sd_mesh.size(); i++) sd_mesh[i].draw(); + for(int i = 0; i < sl_line_mesh.size(); i++)sl_line_mesh[i].draw(); + for(int i = 0; i < sl_pole_mesh.size(); i++)sl_pole_mesh[i].draw(); + for(int i = 0; i < up_mesh.size(); i++) up_mesh[i].draw(); +} + +void VectorMap::drawWireframe (){ + glDisable(GL_DEPTH_TEST); + for(int i = 0; i < re_mesh.size(); i++) re_mesh[i].drawWireframe(); + for(int i = 0; i < gutter_mesh.size(); i++) gutter_mesh[i].drawWireframe(); + for(int i = 0; i < curb_mesh.size(); i++) curb_mesh[i].drawWireframe(); + for(int i = 0; i < wline_mesh.size(); i++) wline_mesh[i].drawWireframe(); + for(int i = 0; i < sline_mesh.size(); i++) sline_mesh[i].drawWireframe(); + for(int i = 0; i < zz_mesh.size(); i++) zz_mesh[i].drawWireframe(); + for(int i = 0; i < cw_mesh.size(); i++) cw_mesh[i].drawWireframe(); + for(int i = 0; i < rsm_mesh.size(); i++) rsm_mesh[i].drawWireframe(); + glEnable(GL_DEPTH_TEST); + for(int i = 0; i < pd_mesh.size(); i++) pd_mesh[i].drawWireframe(); + for(int i = 0; i < sd_mesh.size(); i++) sd_mesh[i].drawWireframe(); + for(int i = 0; i < sl_line_mesh.size(); i++)sl_line_mesh[i].drawWireframe(); + for(int i = 0; i < sl_pole_mesh.size(); i++)sl_pole_mesh[i].drawWireframe(); + for(int i = 0; i < up_mesh.size(); i++) up_mesh[i].drawWireframe(); +} + diff --git a/ui/oculus/ofw/src/vector_map.h b/ui/oculus/ofw/src/vector_map.h new file mode 100644 index 00000000000..b525863c16f --- /dev/null +++ b/ui/oculus/ofw/src/vector_map.h @@ -0,0 +1,296 @@ +// +// vector_map.h +// ORR_PointCloud +// +// Created by Kenjiro on 6/6/15. +// +// + +#ifndef __ORR_PointCloud__vector_map__ +#define __ORR_PointCloud__vector_map__ + +#include "ofMain.h" +#include +#include +#include +#include + +#define FCLIP 40 + +/* for roadedge.csv */ +struct RoadEdge { + int id; + int lid; + int linkid; +}; +/* for gutter.csv, guardrail.csv */ +struct Gutter { + int id; + int aid; + int type; + int linkid; +}; +/* for curb.csv */ +struct Curb { + int id; + int lid; + double height; + double width; + int dir; + int linkid; +}; +/* for whiteline.csv */ +struct WhiteLine { + int id; + int lid; + double width; + char color; + int type; + int linkid; +}; +/* for stopline.csv */ +struct StopLine { + int id; + int lid; + int tlid; + int signid; + int linkid; +}; +/* for zebrazone.csv, sidewalk.csv, crossroads.csv */ +struct ZebraZone { + int id; + int aid; + int linkid; +}; +/* for crosswalk.csv */ +struct CrossWalk { + int id; + int aid; + int type; + int bdid; + int linkid; +}; +/* for road_surface_mark.csv */ +struct RoadSurfaceMark { + int id; + int aid; + std::string type; + int linkid; +}; +/* for poledata.csv, utilitypole.csv */ +struct PoleData { + int id; + int plid; + int linkid; +}; +/* for signaldata.csv, roadsign.csv */ +struct SignalData { + int id; + int vid; + int plid; + int type; + int linkid; +}; +/* for streetlight.csv */ +struct StreetLight { + int id; + int lid; + int plid; + int linkid; +}; +/* basic class */ +/* for point.csv */ +struct PointClass { + int pid; + double b; + double l; + double h; + double bx; + double ly; + double ref; + int mcode1; + int mcode2; + int mcode3; +}; +/* for vector.csv */ +struct VectorClass { + int vid; + int pid; + double hang; + double vang; +}; +/* for line.csv */ +struct LineClass { + int lid; + int bpid; + int fpid; + int blid; + int flid; +}; +/* for area.csv */ +struct AreaClass { + int aid; + int slid; + int elid; +}; +/* for pole.csv */ +struct PoleClass { + int plid; + int vid; + double length; + double dim; +}; +/* for box.csv */ +struct BoxClass { + int bid; + int pid1; + int pid2; + int pid3; + int pid4; + double height; +}; +/* Road data */ +/* for dtlane.csv */ +struct DTLane { + int did; + double dist; + int pid; + double dir; + int apara; + double r; + double slope; + double cant; + double lw; + double rw; +}; +///* for node.csv */ +struct NodeData { + int nid; + int pid; +}; +/* for lane.csv */ +struct LaneData { + int lnid; + int did; + int blid; + int flid; + int bnid; + int fnid; + int jct; + int blid2; + int blid3; + int blid4; + int flid2; + int flid3; + int flid4; + int clossid; + double span; + int lcnt; + int lno; +}; + +class VectorMap +{ +public: + std::map roadedges; + std::map gutters; + std::map curbs; + std::map whitelines; + std::map stoplines; + std::map zebrazones; + std::map crosswalks; + std::map roadsurfacemarks; + std::map poledatas; + std::map roadsigns; + std::map signaldatas; + std::map streetlights; + std::map utilitypoles; + std::map points; + std::map vectors; + std::map lines; + std::map areas; + std::map poles; + std::map boxes; + std::map dtlanes; + std::map nodedatas; + std::map lanedatas; + int read_roadedge(const char* filename); + int read_gutter(const char* filename); + int read_curb(const char* filename); + int read_whiteline(const char* filename); + int read_stopline(const char* filename); + int read_zebrazone(const char* filename); + int read_crosswalk(const char* filename); + int read_roadsurfacemark(const char* filename); + int read_poledata(const char* filename); + int read_roadsign(const char *filename); + int read_signaldata(const char *filename); + int read_streetlight(const char *filename); + int read_utilitypole(const char* filename); + int read_pointclass(const char *filename); + int read_vectorclass(const char *filename); + int read_lineclass(const char *filename); + int read_areaclass(const char *filename); + int read_poleclass(const char *filename); + int read_boxclass(const char *filename); + int read_dtlane(const char *filename); + int read_nodedata(const char *filename); + int read_lanedata(const char *filename); + + void loadAll (const std::string &dirname); + + float min_x, max_x, min_y, max_y; + + void setTF(float mi_x, float ma_x, float mi_y, float ma_y){ + min_x = mi_x; + max_x = ma_x; + min_y = mi_y; + max_y = ma_y; + } + + ofPoint get_point(int pid); + + int set_roadedge(); + int set_gutter(); + int set_curb(); + int set_whiteline(); + int set_stopline(); + int set_zebrazone(); + int set_crosswalk(); + int set_roadsurfacemark(); + int set_poledata(); + int set_roadsign(); + int set_signaldata(); + int set_streetlight(); + int set_utilitypole(); +// int draw_pointclass(); +// int draw_vectorclass(); + ofVboMesh set_lineclass(ofPrimitiveMode mode, ofColor color, float width, int lineid); + ofVboMesh set_areaclass(ofPrimitiveMode mode, ofColor color, int aid); + ofVboMesh set_poleclass(ofColor color, int plid); +// int draw_boxclass(); +// int draw_dtlane(); +// int draw_nodedata(); +// int draw_lanedata(); + + void set_all(); + void draw (); + void drawWireframe (); + + vector re_mesh; + vector gutter_mesh; + vector curb_mesh; + vector wline_mesh; + vector sline_mesh; + vector zz_mesh; + vector cw_mesh; + vector rsm_mesh; + vector pd_mesh; + vector rs_mesh; + vector sd_mesh; + vector sl_line_mesh; + vector sl_pole_mesh; + vector up_mesh; +}; + +#endif /* defined(__ORR_PointCloud__vector_map__) */