Compare commits
11 Commits
46177f166a
...
65415a8355
| Author | SHA1 | Date | |
|---|---|---|---|
| 65415a8355 | |||
| 9069d699be | |||
| 88944d72c2 | |||
| 42814614e3 | |||
| acbddfc828 | |||
| 12d72479aa | |||
| d7ec4d8754 | |||
| 821e6cc0ba | |||
| 1467525ec5 | |||
| 126124c4da | |||
| b3d2fa0ee6 |
@ -59,7 +59,7 @@ find_package(sensor_msgs REQUIRED)
|
|||||||
find_package(pcl_msgs REQUIRED)
|
find_package(pcl_msgs REQUIRED)
|
||||||
find_package(image_transport REQUIRED)
|
find_package(image_transport REQUIRED)
|
||||||
find_package(message_filters REQUIRED)
|
find_package(message_filters REQUIRED)
|
||||||
find_package(yolov3_msg REQUIRED)
|
find_package(pipe_msgs REQUIRED)
|
||||||
|
|
||||||
add_executable(convert_pointcloud_to_depth src/convert_pointcloud_to_depth.cpp)
|
add_executable(convert_pointcloud_to_depth src/convert_pointcloud_to_depth.cpp)
|
||||||
ament_target_dependencies(convert_pointcloud_to_depth ${Libraries} rclcpp_components rclcpp sensor_msgs cv_bridge pcl_conversions image_transport message_filters)
|
ament_target_dependencies(convert_pointcloud_to_depth ${Libraries} rclcpp_components rclcpp sensor_msgs cv_bridge pcl_conversions image_transport message_filters)
|
||||||
@ -78,7 +78,7 @@ include_directories(${Qt5Core_INCLUDE_DIRS} ${Qt5Widgets_INCLUDE_DIRS})
|
|||||||
#ADD_LIBRARY(find_object ${SRC_FILES})
|
#ADD_LIBRARY(find_object ${SRC_FILES})
|
||||||
add_executable(find_pose_node src/FindObjectROS.cpp src/find_pose_node.cpp)
|
add_executable(find_pose_node src/FindObjectROS.cpp src/find_pose_node.cpp)
|
||||||
set_target_properties(find_pose_node PROPERTIES OUTPUT_NAME find_pose_node)
|
set_target_properties(find_pose_node PROPERTIES OUTPUT_NAME find_pose_node)
|
||||||
ament_target_dependencies(find_pose_node rclcpp rclcpp_components yolov3_msg cv_bridge sensor_msgs image_transport message_filters tf2_msgs tf2_geometry_msgs ${AMENT_LIBRARIES})
|
ament_target_dependencies(find_pose_node rclcpp rclcpp_components pipe_msgs cv_bridge sensor_msgs image_transport message_filters tf2_msgs tf2_geometry_msgs ${AMENT_LIBRARIES})
|
||||||
target_link_libraries(find_pose_node Qt5::Core Qt5::Widgets ${OpenCV_LIBRARIES} ${LIBRARIES})
|
target_link_libraries(find_pose_node Qt5::Core Qt5::Widgets ${OpenCV_LIBRARIES} ${LIBRARIES})
|
||||||
|
|
||||||
|
|
||||||
@ -89,7 +89,13 @@ install(TARGETS
|
|||||||
DESTINATION lib/${PROJECT_NAME})
|
DESTINATION lib/${PROJECT_NAME})
|
||||||
|
|
||||||
|
|
||||||
|
#############
|
||||||
|
## Install ##
|
||||||
|
#############
|
||||||
|
install(DIRECTORY
|
||||||
|
launch/.
|
||||||
|
DESTINATION share/${PROJECT_NAME}/launch
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@ -49,8 +49,8 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
|||||||
#include <message_filters/sync_policies/approximate_time.h>
|
#include <message_filters/sync_policies/approximate_time.h>
|
||||||
#include <message_filters/sync_policies/exact_time.h>
|
#include <message_filters/sync_policies/exact_time.h>
|
||||||
#include <sensor_msgs/msg/camera_info.hpp>
|
#include <sensor_msgs/msg/camera_info.hpp>
|
||||||
#include "yolov3_msg/msg/bounding_boxes.hpp"
|
#include "pipe_msgs/msg/bounding_boxes.hpp"
|
||||||
#include "yolov3_msg/msg/bounding_box.hpp"
|
#include "pipe_msgs/msg/bounding_box.hpp"
|
||||||
|
|
||||||
class FindObjectROS
|
class FindObjectROS
|
||||||
{
|
{
|
||||||
@ -71,31 +71,28 @@ private:
|
|||||||
void estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
|
void estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
|
||||||
const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
|
const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
|
||||||
const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg,
|
const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg,
|
||||||
const yolov3_msg::msg::BoundingBoxes::ConstSharedPtr bboxes);
|
const pipe_msgs::msg::BoundingBoxes::ConstSharedPtr bboxes);
|
||||||
double distance(geometry_msgs::msg::TransformStamped point1, geometry_msgs::msg::TransformStamped point2);
|
double distance(geometry_msgs::msg::TransformStamped point1, geometry_msgs::msg::TransformStamped point2);
|
||||||
|
double angular_distance(geometry_msgs::msg::TransformStamped point1, geometry_msgs::msg::TransformStamped point2);
|
||||||
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
rclcpp::Node * node_;
|
rclcpp::Node * node_;
|
||||||
rclcpp::Publisher<std_msgs::msg::Float32MultiArray>::SharedPtr pub_;
|
rclcpp::Publisher<std_msgs::msg::Float32MultiArray>::SharedPtr pub_;
|
||||||
// rclcpp::Publisher<find_object_2d::msg::ObjectsStamped>::SharedPtr pubStamped_;
|
|
||||||
// rclcpp::Publisher<find_object_2d::msg::DetectionInfo>::SharedPtr pubInfo_;
|
|
||||||
|
|
||||||
std::string objFramePrefix_;
|
std::string objFramePrefix_;
|
||||||
bool usePnP_;
|
|
||||||
std::shared_ptr<tf2_ros::TransformBroadcaster> tfBroadcaster_;
|
std::shared_ptr<tf2_ros::TransformBroadcaster> tfBroadcaster_;
|
||||||
unsigned int num_objects_;
|
|
||||||
std::vector<double> objectHeight_;
|
|
||||||
std::vector<double> objectWidth_;
|
|
||||||
image_transport::SubscriberFilter rgbSub_;
|
image_transport::SubscriberFilter rgbSub_;
|
||||||
image_transport::SubscriberFilter depthSub_;
|
image_transport::SubscriberFilter depthSub_;
|
||||||
message_filters::Subscriber<sensor_msgs::msg::CameraInfo> cameraInfoSub_;
|
message_filters::Subscriber<sensor_msgs::msg::CameraInfo> cameraInfoSub_;
|
||||||
message_filters::Subscriber<yolov3_msg::msg::BoundingBoxes> bboxSub_;
|
message_filters::Subscriber<pipe_msgs::msg::BoundingBoxes> bboxSub_;
|
||||||
|
bool tf_broadcast_;
|
||||||
|
|
||||||
typedef message_filters::sync_policies::ApproximateTime<
|
typedef message_filters::sync_policies::ApproximateTime<
|
||||||
sensor_msgs::msg::Image,
|
sensor_msgs::msg::Image,
|
||||||
sensor_msgs::msg::Image,
|
sensor_msgs::msg::Image,
|
||||||
sensor_msgs::msg::CameraInfo,
|
sensor_msgs::msg::CameraInfo,
|
||||||
yolov3_msg::msg::BoundingBoxes> MyApproxSyncPolicy;
|
pipe_msgs::msg::BoundingBoxes> MyApproxSyncPolicy;
|
||||||
message_filters::Synchronizer<MyApproxSyncPolicy> * approxSync_;
|
message_filters::Synchronizer<MyApproxSyncPolicy> * approxSync_;
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
32
ros2_ws/src/find-pose/launch/find-pose-node.launch.py
Normal file
@ -0,0 +1,32 @@
|
|||||||
|
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
|
||||||
|
SetEnvironmentVariable('RCUTILS_LOGGING_USE_STDOUT', '1'),
|
||||||
|
SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '0'),
|
||||||
|
|
||||||
|
# Launch arguments
|
||||||
|
DeclareLaunchArgument('object_prefix', default_value='testingggggg', description='TF prefix of objects.'),
|
||||||
|
|
||||||
|
DeclareLaunchArgument('rgb_topic', default_value='rgb_img', description='Image topic.'),
|
||||||
|
DeclareLaunchArgument('depth_topic', default_value='depth_img', description='Registered depth topic.'),
|
||||||
|
DeclareLaunchArgument('camera_info_topic', default_value='camera_info', description='Camera info topic.'),
|
||||||
|
DeclareLaunchArgument('bounding_box_topic', default_value='bboxes', description='Bouding box topic.'),
|
||||||
|
|
||||||
|
# Nodes to launch
|
||||||
|
Node(
|
||||||
|
package='find-pose', executable='find_pose_node', output='screen',
|
||||||
|
parameters=[{
|
||||||
|
'object_prefix':LaunchConfiguration('object_prefix'),
|
||||||
|
}],
|
||||||
|
remappings=[
|
||||||
|
('rgb_img', LaunchConfiguration('rgb_topic')),
|
||||||
|
('depth_img', LaunchConfiguration('depth_topic')),
|
||||||
|
('camera_info', LaunchConfiguration('camera_info_topic'))]),
|
||||||
|
])
|
||||||
@ -22,14 +22,15 @@
|
|||||||
<exec_depend>cv_bridge</exec_depend>
|
<exec_depend>cv_bridge</exec_depend>
|
||||||
<build_depend>pcl_msgs</build_depend>
|
<build_depend>pcl_msgs</build_depend>
|
||||||
<exec_depend>pcl_msgs</exec_depend>
|
<exec_depend>pcl_msgs</exec_depend>
|
||||||
<build_depend>yolov3_msg</build_depend>
|
<build_depend>pipe_msgs</build_depend>
|
||||||
<exec_depend>yolov3_msg</exec_depend>
|
<exec_depend>pipe_msgs</exec_depend>
|
||||||
<build_depend>image_transport</build_depend>
|
<build_depend>image_transport</build_depend>
|
||||||
<exec_depend>image_transport</exec_depend>
|
<exec_depend>image_transport</exec_depend>
|
||||||
<build_depend>message_filters</build_depend>
|
<build_depend>message_filters</build_depend>
|
||||||
<exec_depend>message_filters</exec_depend>
|
<exec_depend>message_filters</exec_depend>
|
||||||
<test_depend>ament_lint_auto</test_depend>
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
<test_depend>ament_lint_common</test_depend>
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
<exec_depend>ros2launch</exec_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<build_type>ament_cmake</build_type>
|
<build_type>ament_cmake</build_type>
|
||||||
|
|||||||
@ -49,15 +49,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
|||||||
FindObjectROS::FindObjectROS(rclcpp::Node * node) :
|
FindObjectROS::FindObjectROS(rclcpp::Node * node) :
|
||||||
node_(node),
|
node_(node),
|
||||||
objFramePrefix_("object"),
|
objFramePrefix_("object"),
|
||||||
usePnP_(true)
|
tf_broadcast_(true)
|
||||||
{
|
{
|
||||||
int queueSize = 10;
|
int queueSize = 10;
|
||||||
tfBroadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(node);
|
tfBroadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(node);
|
||||||
|
|
||||||
objFramePrefix_ = node->declare_parameter("object_prefix", objFramePrefix_);
|
objFramePrefix_ = node->declare_parameter("object_prefix", objFramePrefix_);
|
||||||
usePnP_ = node->declare_parameter("pnp", usePnP_);
|
|
||||||
RCLCPP_INFO(node->get_logger(), "object_prefix = %s", objFramePrefix_.c_str());
|
RCLCPP_INFO(node->get_logger(), "object_prefix = %s", objFramePrefix_.c_str());
|
||||||
RCLCPP_INFO(node->get_logger(), "pnp = %s", usePnP_?"true":"false");
|
|
||||||
image_transport::TransportHints hints(node);
|
image_transport::TransportHints hints(node);
|
||||||
rgbSub_.subscribe(node, "rgb_img", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
|
rgbSub_.subscribe(node, "rgb_img", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
|
||||||
depthSub_.subscribe(node, "/depth_img", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
|
depthSub_.subscribe(node, "/depth_img", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
|
||||||
@ -66,9 +64,6 @@ FindObjectROS::FindObjectROS(rclcpp::Node * node) :
|
|||||||
|
|
||||||
approxSync_ = new message_filters::Synchronizer<MyApproxSyncPolicy>(MyApproxSyncPolicy(queueSize), rgbSub_, depthSub_, cameraInfoSub_, bboxSub_);
|
approxSync_ = new message_filters::Synchronizer<MyApproxSyncPolicy>(MyApproxSyncPolicy(queueSize), rgbSub_, depthSub_, cameraInfoSub_, bboxSub_);
|
||||||
approxSync_->registerCallback(std::bind(&FindObjectROS::estimate_pose_on_bag, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4));
|
approxSync_->registerCallback(std::bind(&FindObjectROS::estimate_pose_on_bag, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4));
|
||||||
|
|
||||||
num_objects_ = 2;
|
|
||||||
objectHeight_.resize(num_objects_);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -76,9 +71,8 @@ FindObjectROS::FindObjectROS(rclcpp::Node * node) :
|
|||||||
void FindObjectROS::estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
|
void FindObjectROS::estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
|
||||||
const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
|
const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
|
||||||
const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg,
|
const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg,
|
||||||
const yolov3_msg::msg::BoundingBoxes::ConstSharedPtr bboxes)
|
const pipe_msgs::msg::BoundingBoxes::ConstSharedPtr bboxes)
|
||||||
{
|
{
|
||||||
std::cout << "callback!!!!!!!!" << std::endl;
|
|
||||||
if(depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
|
if(depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
|
||||||
depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0)
|
depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0)
|
||||||
{
|
{
|
||||||
@ -106,12 +100,13 @@ void FindObjectROS::estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSha
|
|||||||
}
|
}
|
||||||
|
|
||||||
size_t num_detections = bboxes->bounding_boxes.size();
|
size_t num_detections = bboxes->bounding_boxes.size();
|
||||||
std::cout << "num_detections: " << num_detections << std::endl;
|
std::cout << "Number of detections: " << num_detections << std::endl;
|
||||||
geometry_msgs::msg::TransformStamped left_trail;
|
geometry_msgs::msg::TransformStamped left_trail;
|
||||||
geometry_msgs::msg::TransformStamped right_trail;
|
geometry_msgs::msg::TransformStamped right_trail;
|
||||||
|
std::vector<geometry_msgs::msg::TransformStamped> transforms;
|
||||||
for(size_t i = 0; i < num_detections ; i++)
|
for(size_t i = 0; i < num_detections ; i++)
|
||||||
{
|
{
|
||||||
yolov3_msg::msg::BoundingBox object_bbox = bboxes->bounding_boxes[i];
|
pipe_msgs::msg::BoundingBox object_bbox = bboxes->bounding_boxes[i];
|
||||||
float object_width = object_bbox.xmax - object_bbox.xmin;
|
float object_width = object_bbox.xmax - object_bbox.xmin;
|
||||||
float object_height = object_bbox.ymax - object_bbox.ymin;
|
float object_height = object_bbox.ymax - object_bbox.ymin;
|
||||||
// top left is the 0,0
|
// top left is the 0,0
|
||||||
@ -127,10 +122,15 @@ void FindObjectROS::estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSha
|
|||||||
if (object_class == std::string("r_trail"))
|
if (object_class == std::string("r_trail"))
|
||||||
right_trail = pose;
|
right_trail = pose;
|
||||||
std::cout << "Pose for "<< object_class << " x: " << pose.transform.translation.x << " y: " << pose.transform.translation.y << " z: " << pose.transform.translation.z << std::endl;
|
std::cout << "Pose for "<< object_class << " x: " << pose.transform.translation.x << " y: " << pose.transform.translation.y << " z: " << pose.transform.translation.z << std::endl;
|
||||||
|
transforms.push_back(pose);
|
||||||
}
|
}
|
||||||
// geometry_msgs::msg::TransformStamped right_trail = estimate_pose(image, ptrDepth->image, 115, 116, cv::Point2f(819,600), cv::Point2f(974,600), cv::Point2f(974,716), cv::Point2f(819,716));
|
if(tf_broadcast_ && transforms.size())
|
||||||
// geometry_msgs::msg::TransformStamped left_trail = estimate_pose(image, ptrDepth->image, 160, 168, cv::Point2f(350,548), cv::Point2f(510,548), cv::Point2f(510,716), cv::Point2f(350,716));
|
{
|
||||||
std::cout << "Distance in meters !!!!!!" << distance(left_trail, right_trail) << std::endl;
|
std::cout << "broadcast tf" << std::endl;
|
||||||
|
tfBroadcaster_->sendTransform(transforms);
|
||||||
|
}
|
||||||
|
std::cout << "Euclidean distance between two pipes in meters !!!!!!" << distance(left_trail, right_trail) << std::endl;
|
||||||
|
std::cout << "Angular distance between two pipes in radians !!!!!!" << angular_distance(left_trail, right_trail) << std::endl;
|
||||||
std::cout << std::endl;
|
std::cout << std::endl;
|
||||||
}
|
}
|
||||||
catch(const cv_bridge::Exception & e)
|
catch(const cv_bridge::Exception & e)
|
||||||
@ -142,16 +142,6 @@ void FindObjectROS::estimate_pose_on_bag(const sensor_msgs::msg::Image::ConstSha
|
|||||||
|
|
||||||
geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_image, cv::Mat depth, float objectWidth, float objectHeight, cv::Point2f point_1, cv::Point2f point_2, cv::Point2f point_3, cv::Point2f point_4)
|
geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_image, cv::Mat depth, float objectWidth, float objectHeight, cv::Point2f point_1, cv::Point2f point_2, cv::Point2f point_3, cv::Point2f point_4)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
std::vector<geometry_msgs::msg::TransformStamped> transforms;
|
|
||||||
// store bounding boxes. (This should come from yolo ideally)
|
|
||||||
// float objectWidth = 160; // width of bounding box in pixels
|
|
||||||
// float objectHeight = 168; // height of bounding box in pixels
|
|
||||||
// float objectWidth = 155; // width of bounding box in pixels
|
|
||||||
// float objectHeight = 116; // height of bounding box in pixels
|
|
||||||
|
|
||||||
|
|
||||||
geometry_msgs::msg::TransformStamped transform;
|
geometry_msgs::msg::TransformStamped transform;
|
||||||
transform.transform.rotation.x=0;
|
transform.transform.rotation.x=0;
|
||||||
transform.transform.rotation.y=0;
|
transform.transform.rotation.y=0;
|
||||||
@ -160,12 +150,10 @@ geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_im
|
|||||||
transform.transform.translation.x=0;
|
transform.transform.translation.x=0;
|
||||||
transform.transform.translation.y=0;
|
transform.transform.translation.y=0;
|
||||||
transform.transform.translation.z=0;
|
transform.transform.translation.z=0;
|
||||||
transform.child_frame_id = "l_trail";
|
transform.child_frame_id = "";
|
||||||
transform.header.frame_id = "camera_link";
|
transform.header.frame_id = "camera_link";
|
||||||
// transform.header.stamp.sec = ros::Time::now();
|
|
||||||
tf2::Quaternion q;
|
tf2::Quaternion q;
|
||||||
float depthConstant = 1.0f/640.8887939453125; // 0.00156033 // 1.0f/cameraInfoMsg->K[4];
|
float depthConstant = 1.0f/640.8887939453125; // 0.00156033 // 1.0f/cameraInfoMsg->K[4];
|
||||||
// std::cout << "depthconstant: " << depthConstant << std::endl;
|
|
||||||
std::vector<cv::Point3f> objectPoints(4);
|
std::vector<cv::Point3f> objectPoints(4);
|
||||||
std::vector<cv::Point2f> imagePoints(4);
|
std::vector<cv::Point2f> imagePoints(4);
|
||||||
objectPoints[0] = cv::Point3f(-0.5, -(objectHeight/objectWidth)/2.0f,0);
|
objectPoints[0] = cv::Point3f(-0.5, -(objectHeight/objectWidth)/2.0f,0);
|
||||||
@ -173,14 +161,6 @@ geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_im
|
|||||||
objectPoints[2] = cv::Point3f(0.5,(objectHeight/objectWidth)/2.0f,0);
|
objectPoints[2] = cv::Point3f(0.5,(objectHeight/objectWidth)/2.0f,0);
|
||||||
objectPoints[3] = cv::Point3f(-0.5,(objectHeight/objectWidth)/2.0f,0);
|
objectPoints[3] = cv::Point3f(-0.5,(objectHeight/objectWidth)/2.0f,0);
|
||||||
// QPointF pt = iter->map(QPointF(0, 0));
|
// QPointF pt = iter->map(QPointF(0, 0));
|
||||||
// imagePoints[0] = cv::Point2f(350,548);
|
|
||||||
// // pt = iter->map(QPointF(objectWidth, 0));
|
|
||||||
// imagePoints[1] = cv::Point2f(510,548);
|
|
||||||
// // pt = iter->map(QPointF(objectWidth, objectHeight));
|
|
||||||
// imagePoints[2] = cv::Point2f(510,716);
|
|
||||||
// // pt = iter->map(QPointF(0, objectHeight));
|
|
||||||
// imagePoints[3] = cv::Point2f(350,716);
|
|
||||||
// QPointF pt = iter->map(QPointF(0, 0));
|
|
||||||
imagePoints[0] = point_1;
|
imagePoints[0] = point_1;
|
||||||
// pt = iter->map(QPointF(objectWidth, 0));
|
// pt = iter->map(QPointF(objectWidth, 0));
|
||||||
imagePoints[1] = point_2;
|
imagePoints[1] = point_2;
|
||||||
@ -200,7 +180,7 @@ geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_im
|
|||||||
cv::Mat tvec(1,3, CV_64FC1);
|
cv::Mat tvec(1,3, CV_64FC1);
|
||||||
cv::solvePnP(objectPoints, imagePoints, cameraMatrix, distCoeffs, rvec, tvec);
|
cv::solvePnP(objectPoints, imagePoints, cameraMatrix, distCoeffs, rvec, tvec);
|
||||||
|
|
||||||
// std::cout << "Pose tvec x: " << tvec.at<double>(0) << " y: " << tvec.at<double>(1) << " z: " << tvec.at<double>(2) << std::endl;
|
// std::cout << "Pose tvec x: " << tvec.at<double>(0) << " y: " << tvec.at<double>(1) << " z: " << tvec.at<double>(2) << std::endl;
|
||||||
|
|
||||||
cv::Mat R;
|
cv::Mat R;
|
||||||
cv::Rodrigues(rvec, R);
|
cv::Rodrigues(rvec, R);
|
||||||
@ -216,8 +196,8 @@ geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_im
|
|||||||
center.x()+0.5f, center.y()+0.5f,
|
center.x()+0.5f, center.y()+0.5f,
|
||||||
float(depth.cols/2)-0.5f, float(depth.rows/2)-0.5f,
|
float(depth.cols/2)-0.5f, float(depth.rows/2)-0.5f,
|
||||||
1.0f/depthConstant, 1.0f/depthConstant);
|
1.0f/depthConstant, 1.0f/depthConstant);
|
||||||
// std::cout << "center x: " << center.x() << " y: " << center.y() << std::endl;
|
// std::cout << "center x: " << center.x() << " y: " << center.y() << std::endl;
|
||||||
// std::cout << "center 3D x: " << center3D[0] << " y: " << center3D[1] <<" z: " << center3D[1] << std::endl;
|
// std::cout << "center 3D x: " << center3D[0] << " y: " << center3D[1] <<" z: " << center3D[1] << std::endl;
|
||||||
|
|
||||||
transform.transform.translation.x = tvec.at<double>(0)*(center3D.val[2]/tvec.at<double>(2));
|
transform.transform.translation.x = tvec.at<double>(0)*(center3D.val[2]/tvec.at<double>(2));
|
||||||
transform.transform.translation.y = tvec.at<double>(1)*(center3D.val[2]/tvec.at<double>(2));
|
transform.transform.translation.y = tvec.at<double>(1)*(center3D.val[2]/tvec.at<double>(2));
|
||||||
@ -228,12 +208,7 @@ geometry_msgs::msg::TransformStamped FindObjectROS::estimate_pose(cv::Mat rgb_im
|
|||||||
q2.setRPY(CV_PI/2.0, CV_PI/2.0, 0);
|
q2.setRPY(CV_PI/2.0, CV_PI/2.0, 0);
|
||||||
q *= q2;
|
q *= q2;
|
||||||
transform.transform.rotation = tf2::toMsg(q.normalized());
|
transform.transform.rotation = tf2::toMsg(q.normalized());
|
||||||
transforms.push_back(transform);
|
|
||||||
return transform;
|
return transform;
|
||||||
// if(transforms.size())
|
|
||||||
// {
|
|
||||||
// tfBroadcaster_->sendTransform(transforms);
|
|
||||||
// }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
cv::Vec3f FindObjectROS::getDepth(const cv::Mat & depthImage,
|
cv::Vec3f FindObjectROS::getDepth(const cv::Mat & depthImage,
|
||||||
@ -273,7 +248,6 @@ cv::Vec3f FindObjectROS::getDepth(const cv::Mat & depthImage,
|
|||||||
bool isValid;
|
bool isValid;
|
||||||
if(isInMM)
|
if(isInMM)
|
||||||
{
|
{
|
||||||
// std::cout << "depth is in mm!!" << std::endl;
|
|
||||||
depth = (float)depthImage.at<uint16_t>(y,x);
|
depth = (float)depthImage.at<uint16_t>(y,x);
|
||||||
isValid = depth != 0.0f;
|
isValid = depth != 0.0f;
|
||||||
}
|
}
|
||||||
@ -282,14 +256,12 @@ cv::Vec3f FindObjectROS::getDepth(const cv::Mat & depthImage,
|
|||||||
|
|
||||||
depth = depthImage.at<float>(y,x);
|
depth = depthImage.at<float>(y,x);
|
||||||
isValid = std::isfinite(depth) && depth > 0.0f;
|
isValid = std::isfinite(depth) && depth > 0.0f;
|
||||||
// std::cout << "depth is NOT in mm!! " << depth << std::endl;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check for invalid measurements
|
// Check for invalid measurements
|
||||||
if (!isValid)
|
if (!isValid)
|
||||||
{
|
{
|
||||||
pt.val[0] = pt.val[1] = pt.val[2] = bad_point;
|
pt.val[0] = pt.val[1] = pt.val[2] = bad_point;
|
||||||
// std::cout << "depth pt: " << pt.val[0] << " y: " << pt.val[1] << " z: " << pt.val[2] << std::endl;
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@ -297,7 +269,7 @@ cv::Vec3f FindObjectROS::getDepth(const cv::Mat & depthImage,
|
|||||||
pt.val[0] = (float(x) - center_x) * depth * constant_x;
|
pt.val[0] = (float(x) - center_x) * depth * constant_x;
|
||||||
pt.val[1] = (float(y) - center_y) * depth * constant_y;
|
pt.val[1] = (float(y) - center_y) * depth * constant_y;
|
||||||
pt.val[2] = depth*unit_scaling;
|
pt.val[2] = depth*unit_scaling;
|
||||||
// td::cout << "depth pt: " << pt.val[0] << " y: " << pt.val[1] << " z: " << pt.val[2] << std::endl;
|
// std::cout << "depth pt: " << pt.val[0] << " y: " << pt.val[1] << " z: " << pt.val[2] << std::endl;
|
||||||
}
|
}
|
||||||
return pt;
|
return pt;
|
||||||
}
|
}
|
||||||
@ -310,3 +282,21 @@ double FindObjectROS::distance(geometry_msgs::msg::TransformStamped point1, geom
|
|||||||
vector.z = point2.transform.translation.z - point1.transform.translation.z;
|
vector.z = point2.transform.translation.z - point1.transform.translation.z;
|
||||||
return std::sqrt(vector.x*vector.x + vector.y*vector.y + vector.z*vector.z);
|
return std::sqrt(vector.x*vector.x + vector.y*vector.y + vector.z*vector.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
double FindObjectROS::angular_distance(geometry_msgs::msg::TransformStamped point1, geometry_msgs::msg::TransformStamped point2)
|
||||||
|
{
|
||||||
|
tf2::Quaternion quat1(point1.transform.rotation.x, point1.transform.rotation.y, point1.transform.rotation.z, point1.transform.rotation.w);
|
||||||
|
tf2::Quaternion quat2(point2.transform.rotation.x, point2.transform.rotation.y, point2.transform.rotation.z, point2.transform.rotation.w);
|
||||||
|
|
||||||
|
// Assume that 'pos1' and 'pos2' are the positions of the two points
|
||||||
|
// and 'quat1' and 'quat2' are their corresponding quaternions
|
||||||
|
tf2::Vector3 diff;
|
||||||
|
diff[0] = point2.transform.translation.x - point1.transform.translation.x;
|
||||||
|
diff[1] = point2.transform.translation.y - point1.transform.translation.y;
|
||||||
|
diff[2] = point2.transform.translation.z - point1.transform.translation.z;
|
||||||
|
tf2::Quaternion rot = quat2 * quat1.inverse();
|
||||||
|
tf2::Quaternion diff_quat(0, diff.getX(), diff.getY(), diff.getZ());
|
||||||
|
tf2::Quaternion result = rot * diff_quat * rot.inverse();
|
||||||
|
double angle = 2 * std::acos(result.getW());
|
||||||
|
return angle;
|
||||||
|
}
|
||||||
|
|||||||
36
ros2_ws/src/pipe_msgs/CMakeLists.txt
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.8)
|
||||||
|
project(pipe_msgs)
|
||||||
|
|
||||||
|
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||||
|
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# find dependencies
|
||||||
|
find_package(ament_cmake REQUIRED)
|
||||||
|
# uncomment the following section in order to fill in
|
||||||
|
# further dependencies manually.
|
||||||
|
# find_package(<dependency> REQUIRED)
|
||||||
|
|
||||||
|
if(BUILD_TESTING)
|
||||||
|
find_package(ament_lint_auto REQUIRED)
|
||||||
|
# the following line skips the linter which checks for copyrights
|
||||||
|
# comment the line when a copyright and license is added to all source files
|
||||||
|
set(ament_cmake_copyright_FOUND TRUE)
|
||||||
|
# the following line skips cpplint (only works in a git repo)
|
||||||
|
# comment the line when this package is in a git repo and when
|
||||||
|
# a copyright and license is added to all source files
|
||||||
|
set(ament_cmake_cpplint_FOUND TRUE)
|
||||||
|
ament_lint_auto_find_test_dependencies()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
|
||||||
|
find_package(std_msgs REQUIRED)
|
||||||
|
find_package(rosidl_default_generators REQUIRED)
|
||||||
|
|
||||||
|
rosidl_generate_interfaces(${PROJECT_NAME}
|
||||||
|
"msg/BoundingBox.msg"
|
||||||
|
"msg/BoundingBoxes.msg"
|
||||||
|
DEPENDENCIES std_msgs # Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg
|
||||||
|
)
|
||||||
|
|
||||||
|
ament_package()
|
||||||
22
ros2_ws/src/pipe_msgs/package.xml
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>pipe_msgs</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>TODO: Package description</description>
|
||||||
|
<maintainer email="eic.apoorva@gmail.com">parallels</maintainer>
|
||||||
|
<license>TODO: License declaration</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
<depend>std_msgs</depend>
|
||||||
|
<build_depend>rosidl_default_generators</build_depend>
|
||||||
|
<exec_depend>rosidl_default_runtime</exec_depend>
|
||||||
|
<member_of_group>rosidl_interface_packages</member_of_group>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
|
Before Width: | Height: | Size: 160 KiB |
|
Before Width: | Height: | Size: 93 KiB |
|
Before Width: | Height: | Size: 92 KiB |
|
Before Width: | Height: | Size: 151 KiB |
|
Before Width: | Height: | Size: 93 KiB |
@ -1,28 +0,0 @@
|
|||||||
lr0: 0.01
|
|
||||||
lrf: 0.1
|
|
||||||
momentum: 0.937
|
|
||||||
weight_decay: 0.0005
|
|
||||||
warmup_epochs: 3.0
|
|
||||||
warmup_momentum: 0.8
|
|
||||||
warmup_bias_lr: 0.1
|
|
||||||
box: 0.05
|
|
||||||
cls: 0.5
|
|
||||||
cls_pw: 1.0
|
|
||||||
obj: 1.0
|
|
||||||
obj_pw: 1.0
|
|
||||||
iou_t: 0.2
|
|
||||||
anchor_t: 4.0
|
|
||||||
fl_gamma: 0.0
|
|
||||||
hsv_h: 0.015
|
|
||||||
hsv_s: 0.7
|
|
||||||
hsv_v: 0.4
|
|
||||||
degrees: 0.0
|
|
||||||
translate: 0.1
|
|
||||||
scale: 0.5
|
|
||||||
shear: 0.0
|
|
||||||
perspective: 0.0
|
|
||||||
flipud: 0.0
|
|
||||||
fliplr: 0.5
|
|
||||||
mosaic: 1.0
|
|
||||||
mixup: 0.0
|
|
||||||
copy_paste: 0.0
|
|
||||||
|
Before Width: | Height: | Size: 161 KiB |
|
Before Width: | Height: | Size: 198 KiB |
@ -1,37 +0,0 @@
|
|||||||
weights: ''
|
|
||||||
cfg: /content/gdrive/MyDrive/yolov3/models/yolov3.yaml
|
|
||||||
data: data/custom-yolov3.yaml
|
|
||||||
hyp: data/hyps/hyp.scratch.yaml
|
|
||||||
epochs: 300
|
|
||||||
batch_size: 16
|
|
||||||
imgsz: 1280
|
|
||||||
rect: false
|
|
||||||
resume: false
|
|
||||||
nosave: false
|
|
||||||
noval: false
|
|
||||||
noautoanchor: false
|
|
||||||
evolve: null
|
|
||||||
bucket: ''
|
|
||||||
cache: null
|
|
||||||
image_weights: false
|
|
||||||
device: ''
|
|
||||||
multi_scale: false
|
|
||||||
single_cls: false
|
|
||||||
adam: false
|
|
||||||
sync_bn: false
|
|
||||||
workers: 8
|
|
||||||
project: runs/train
|
|
||||||
name: exp
|
|
||||||
exist_ok: false
|
|
||||||
quad: false
|
|
||||||
linear_lr: false
|
|
||||||
label_smoothing: 0.0
|
|
||||||
patience: 100
|
|
||||||
freeze: 0
|
|
||||||
save_period: -1
|
|
||||||
local_rank: -1
|
|
||||||
entity: null
|
|
||||||
upload_dataset: false
|
|
||||||
bbox_interval: -1
|
|
||||||
artifact_alias: latest
|
|
||||||
save_dir: runs/train/exp15
|
|
||||||
@ -1,301 +0,0 @@
|
|||||||
epoch, train/box_loss, train/obj_loss, train/cls_loss, metrics/precision, metrics/recall, metrics/mAP_0.5,metrics/mAP_0.5:0.95, val/box_loss, val/obj_loss, val/cls_loss, x/lr0, x/lr1, x/lr2
|
|
||||||
0, 0.1072, 0.089784, 0.045148, 3.1447e-05, 0.009434, 1.7021e-05, 1.7021e-06, 0.074383, 0.071557, 0.036102, 0.00019, 0.00019, 0.09829
|
|
||||||
1, 0.09357, 0.073808, 0.04392, 6.2893e-05, 0.018868, 3.5032e-05, 6.2107e-06, 0.069977, 0.066751, 0.035672, 0.00038999, 0.00038999, 0.09649
|
|
||||||
2, 0.082933, 0.073286, 0.042061, 6.2893e-05, 0.018868, 3.5252e-05, 3.5252e-06, 0.067869, 0.065488, 0.035208, 0.00058994, 0.00058994, 0.09469
|
|
||||||
3, 0.078388, 0.073047, 0.042215, 9.434e-05, 0.028302, 5.6751e-05, 5.6751e-06, 0.067291, 0.064494, 0.034919, 0.00078982, 0.00078982, 0.09289
|
|
||||||
4, 0.077606, 0.066943, 0.040052, 9.434e-05, 0.028302, 5.7173e-05, 9.217e-06, 0.065971, 0.064303, 0.034521, 0.00098961, 0.00098961, 0.09109
|
|
||||||
5, 0.073009, 0.072096, 0.039418, 0.0010693, 0.082038, 0.00067087, 0.00010067, 0.065407, 0.064251, 0.034196, 0.0011893, 0.0011893, 0.089289
|
|
||||||
6, 0.074801, 0.071712, 0.039586, 0.0010178, 0.16158, 0.00093658, 0.00021294, 0.065921, 0.063458, 0.033979, 0.0013888, 0.0013888, 0.087489
|
|
||||||
7, 0.076127, 0.0702, 0.039439, 0.00084618, 0.17629, 0.0011685, 0.00023231, 0.065714, 0.063461, 0.033674, 0.0015881, 0.0015881, 0.085688
|
|
||||||
8, 0.075849, 0.074078, 0.038786, 0.0092778, 0.030889, 0.0032644, 0.00070873, 0.065679, 0.062307, 0.030542, 0.0017872, 0.0017872, 0.083887
|
|
||||||
9, 0.075436, 0.069392, 0.038983, 0.0060257, 0.10055, 0.0033271, 0.00079476, 0.064516, 0.062611, 0.030316, 0.001986, 0.001986, 0.082086
|
|
||||||
10, 0.077201, 0.071009, 0.035982, 0.015542, 0.070484, 0.005924, 0.0010521, 0.070791, 0.061645, 0.026312, 0.0021846, 0.0021846, 0.080285
|
|
||||||
11, 0.07411, 0.067135, 0.036761, 0.54391, 0.014074, 0.0064732, 0.0012823, 0.079597, 0.077907, 0.033935, 0.0023829, 0.0023829, 0.078483
|
|
||||||
12, 0.072703, 0.066995, 0.036249, 0.015042, 0.15315, 0.0083551, 0.0012464, 0.075651, 0.067622, 0.028427, 0.0025808, 0.0025808, 0.076681
|
|
||||||
13, 0.0737, 0.072585, 0.03594, 0.038881, 0.15844, 0.020356, 0.0033538, 0.063492, 0.061259, 0.026789, 0.0027784, 0.0027784, 0.074878
|
|
||||||
14, 0.072014, 0.072332, 0.036173, 0.036296, 0.10895, 0.018669, 0.003782, 0.061362, 0.061768, 0.026689, 0.0029756, 0.0029756, 0.073076
|
|
||||||
15, 0.072346, 0.071417, 0.033542, 0.090208, 0.14203, 0.0267, 0.0043627, 0.062477, 0.06224, 0.024864, 0.0031723, 0.0031723, 0.071272
|
|
||||||
16, 0.070106, 0.068058, 0.034502, 0.067812, 0.14637, 0.037359, 0.0078725, 0.06237, 0.061756, 0.02467, 0.0033686, 0.0033686, 0.069469
|
|
||||||
17, 0.074946, 0.064136, 0.032574, 0.13835, 0.12299, 0.072165, 0.012966, 0.058928, 0.05861, 0.024038, 0.0035645, 0.0035645, 0.067664
|
|
||||||
18, 0.070358, 0.060051, 0.031907, 0.0479, 0.25203, 0.038178, 0.0060513, 0.05915, 0.058207, 0.025925, 0.0037598, 0.0037598, 0.06586
|
|
||||||
19, 0.067322, 0.055626, 0.03065, 0.82252, 0.060739, 0.063727, 0.012951, 0.065587, 0.053063, 0.021251, 0.0039546, 0.0039546, 0.064055
|
|
||||||
20, 0.068843, 0.057321, 0.030782, 0.18588, 0.17522, 0.10052, 0.0231, 0.057125, 0.052086, 0.021309, 0.0041488, 0.0041488, 0.062249
|
|
||||||
21, 0.06779, 0.056333, 0.030423, 0.14705, 0.2448, 0.14866, 0.026988, 0.057788, 0.054503, 0.020962, 0.0043424, 0.0043424, 0.060442
|
|
||||||
22, 0.065426, 0.052589, 0.030872, 0.31674, 0.30232, 0.25582, 0.068044, 0.051682, 0.048209, 0.020117, 0.0045354, 0.0045354, 0.058635
|
|
||||||
23, 0.067626, 0.056669, 0.027687, 0.10589, 0.17271, 0.068596, 0.015701, 0.064839, 0.051478, 0.020254, 0.0047278, 0.0047278, 0.056828
|
|
||||||
24, 0.059718, 0.052035, 0.026036, 0.42306, 0.42077, 0.40239, 0.11784, 0.055993, 0.041789, 0.015245, 0.0049195, 0.0049195, 0.055019
|
|
||||||
25, 0.066427, 0.060109, 0.026517, 0.21072, 0.40616, 0.23959, 0.044691, 0.060816, 0.050553, 0.017379, 0.0051104, 0.0051104, 0.05321
|
|
||||||
26, 0.068186, 0.057706, 0.026478, 0.14783, 0.51256, 0.19894, 0.060068, 0.057491, 0.04908, 0.018394, 0.0053007, 0.0053007, 0.051401
|
|
||||||
27, 0.066612, 0.050319, 0.024494, 0.48579, 0.42298, 0.40479, 0.11374, 0.056078, 0.045788, 0.014807, 0.0054901, 0.0054901, 0.04959
|
|
||||||
28, 0.063534, 0.052454, 0.024039, 0.40719, 0.36156, 0.30722, 0.10794, 0.055933, 0.046081, 0.021163, 0.0056788, 0.0056788, 0.047779
|
|
||||||
29, 0.063979, 0.050578, 0.023715, 0.11747, 0.27502, 0.089202, 0.017614, 0.058407, 0.055614, 0.019128, 0.0058667, 0.0058667, 0.045967
|
|
||||||
30, 0.061931, 0.04879, 0.021555, 0.097, 0.14031, 0.055955, 0.0091582, 0.056716, 0.063297, 0.024825, 0.0060537, 0.0060537, 0.044154
|
|
||||||
31, 0.057106, 0.050596, 0.020186, 0.46931, 0.63839, 0.47727, 0.14214, 0.047358, 0.044311, 0.013691, 0.0062398, 0.0062398, 0.04234
|
|
||||||
32, 0.061115, 0.046957, 0.020035, 0.63103, 0.71706, 0.687, 0.25922, 0.046848, 0.037924, 0.011027, 0.006425, 0.006425, 0.040525
|
|
||||||
33, 0.056406, 0.046535, 0.01865, 0.43884, 0.62161, 0.51021, 0.17632, 0.05008, 0.038613, 0.014262, 0.0066094, 0.0066094, 0.038709
|
|
||||||
34, 0.059193, 0.048328, 0.019087, 0.40999, 0.66487, 0.53293, 0.19979, 0.047951, 0.038267, 0.0089096, 0.0067927, 0.0067927, 0.036893
|
|
||||||
35, 0.058858, 0.046026, 0.018089, 0.49914, 0.45985, 0.44086, 0.14173, 0.055914, 0.049698, 0.016622, 0.0069751, 0.0069751, 0.035075
|
|
||||||
36, 0.05378, 0.046878, 0.017436, 0.54042, 0.40374, 0.42118, 0.12772, 0.053832, 0.048224, 0.015295, 0.0071565, 0.0071565, 0.033256
|
|
||||||
37, 0.057157, 0.047375, 0.01825, 0.45283, 0.17341, 0.1188, 0.023888, 0.05297, 0.06591, 0.028537, 0.0073368, 0.0073368, 0.031437
|
|
||||||
38, 0.055086, 0.044643, 0.016019, 0.59048, 0.58181, 0.54786, 0.20768, 0.046944, 0.041786, 0.011842, 0.0075161, 0.0075161, 0.029616
|
|
||||||
39, 0.052514, 0.042485, 0.016678, 0.60654, 0.62859, 0.65293, 0.27689, 0.04138, 0.043998, 0.0078349, 0.0076943, 0.0076943, 0.027794
|
|
||||||
40, 0.054016, 0.045163, 0.016713, 0.43989, 0.24508, 0.23914, 0.074126, 0.052986, 0.055093, 0.029361, 0.0078714, 0.0078714, 0.025971
|
|
||||||
41, 0.052897, 0.042598, 0.014125, 0.66111, 0.45699, 0.54765, 0.20954, 0.04524, 0.048015, 0.013144, 0.0080473, 0.0080473, 0.024147
|
|
||||||
42, 0.051021, 0.042313, 0.012967, 0.64228, 0.50983, 0.5556, 0.2054, 0.049423, 0.04853, 0.014758, 0.0082221, 0.0082221, 0.022322
|
|
||||||
43, 0.05275, 0.041908, 0.012555, 0.76316, 0.7306, 0.72312, 0.21781, 0.046986, 0.032759, 0.0042896, 0.0083957, 0.0083957, 0.020496
|
|
||||||
44, 0.052692, 0.040748, 0.012202, 0.73323, 0.7009, 0.74501, 0.32735, 0.040507, 0.036143, 0.0074856, 0.0085681, 0.0085681, 0.018668
|
|
||||||
45, 0.051049, 0.040343, 0.010494, 0.79341, 0.8425, 0.8331, 0.38394, 0.042813, 0.033749, 0.0054575, 0.0087393, 0.0087393, 0.016839
|
|
||||||
46, 0.052916, 0.04602, 0.016315, 0.0074664, 0.36345, 0.0069738, 0.0012171, 0.071852, 0.057659, 0.040379, 0.0089092, 0.0089092, 0.015009
|
|
||||||
47, 0.061261, 0.055108, 0.025584, 0, 0, 0, 0, 0.10342, 0.10308, 0.61562, 0.0090778, 0.0090778, 0.013178
|
|
||||||
48, 0.055741, 0.048942, 0.022914, 0, 0, 0, 0, 0.091703, 0.15503, 0.50829, 0.0092451, 0.0092451, 0.011345
|
|
||||||
49, 0.055505, 0.046065, 0.01996, 0.40454, 0.43583, 0.36731, 0.1155, 0.054668, 0.048338, 0.01677, 0.009411, 0.009411, 0.009511
|
|
||||||
50, 0.052316, 0.04637, 0.01857, 0.29994, 0.17425, 0.1908, 0.069672, 0.061657, 0.058302, 0.017473, 0.0093971, 0.0093971, 0.0093971
|
|
||||||
51, 0.052513, 0.044853, 0.016164, 0.32316, 0.21994, 0.18133, 0.052024, 0.054571, 0.052566, 0.018779, 0.0093971, 0.0093971, 0.0093971
|
|
||||||
52, 0.050169, 0.041122, 0.013702, 0.71349, 0.46749, 0.50083, 0.20943, 0.05027, 0.040049, 0.0090618, 0.0093733, 0.0093733, 0.0093733
|
|
||||||
53, 0.052356, 0.038377, 0.012993, 0.70745, 0.58166, 0.63794, 0.29499, 0.043828, 0.039433, 0.006337, 0.0093491, 0.0093491, 0.0093491
|
|
||||||
54, 0.049593, 0.041015, 0.013021, 0.8286, 0.83119, 0.85701, 0.39813, 0.044484, 0.031344, 0.0039315, 0.0093245, 0.0093245, 0.0093245
|
|
||||||
55, 0.050457, 0.040325, 0.011648, 0.90411, 0.72727, 0.81333, 0.32555, 0.050267, 0.031773, 0.0036776, 0.0092995, 0.0092995, 0.0092995
|
|
||||||
56, 0.048361, 0.037615, 0.01134, 0.83214, 0.70918, 0.7804, 0.32044, 0.048583, 0.035312, 0.0075229, 0.009274, 0.009274, 0.009274
|
|
||||||
57, 0.045264, 0.037444, 0.010766, 0.73705, 0.60835, 0.67841, 0.33454, 0.037938, 0.035844, 0.011167, 0.0092481, 0.0092481, 0.0092481
|
|
||||||
58, 0.048281, 0.038769, 0.0095906, 0.77539, 0.72818, 0.77761, 0.35702, 0.038495, 0.033515, 0.0052658, 0.0092219, 0.0092219, 0.0092219
|
|
||||||
59, 0.045365, 0.036449, 0.0083486, 0.84428, 0.80126, 0.86356, 0.45554, 0.039402, 0.029563, 0.00649, 0.0091952, 0.0091952, 0.0091952
|
|
||||||
60, 0.047082, 0.038087, 0.01002, 0.82263, 0.84693, 0.89213, 0.45806, 0.038933, 0.03161, 0.0054989, 0.0091681, 0.0091681, 0.0091681
|
|
||||||
61, 0.043742, 0.036556, 0.0088003, 0.92037, 0.8607, 0.9257, 0.48197, 0.036326, 0.030955, 0.0034465, 0.0091406, 0.0091406, 0.0091406
|
|
||||||
62, 0.044255, 0.036951, 0.010437, 0.87895, 0.89227, 0.91443, 0.44407, 0.043374, 0.028684, 0.0026665, 0.0091127, 0.0091127, 0.0091127
|
|
||||||
63, 0.045161, 0.03555, 0.0089086, 0.92405, 0.88652, 0.91847, 0.5026, 0.039014, 0.030431, 0.0025694, 0.0090844, 0.0090844, 0.0090844
|
|
||||||
64, 0.045083, 0.037143, 0.0087739, 0.93807, 0.88789, 0.93251, 0.48687, 0.041815, 0.028742, 0.002422, 0.0090557, 0.0090557, 0.0090557
|
|
||||||
65, 0.040342, 0.037515, 0.0077562, 0.92831, 0.92405, 0.95091, 0.55001, 0.033787, 0.028646, 0.0023556, 0.0090266, 0.0090266, 0.0090266
|
|
||||||
66, 0.044417, 0.032584, 0.0076607, 0.92958, 0.86946, 0.92922, 0.53225, 0.035044, 0.028907, 0.0025468, 0.0089972, 0.0089972, 0.0089972
|
|
||||||
67, 0.039694, 0.035995, 0.0079306, 0.88746, 0.90617, 0.92104, 0.51225, 0.035307, 0.027231, 0.003196, 0.0089673, 0.0089673, 0.0089673
|
|
||||||
68, 0.044565, 0.034608, 0.0088018, 0.87307, 0.84145, 0.90489, 0.50325, 0.034845, 0.032796, 0.0049277, 0.0089371, 0.0089371, 0.0089371
|
|
||||||
69, 0.042965, 0.033984, 0.01085, 0.9106, 0.85758, 0.91816, 0.51602, 0.035491, 0.030649, 0.0044527, 0.0089065, 0.0089065, 0.0089065
|
|
||||||
70, 0.04196, 0.035426, 0.0084481, 0.86355, 0.90502, 0.92138, 0.55436, 0.032832, 0.029249, 0.0028974, 0.0088755, 0.0088755, 0.0088755
|
|
||||||
71, 0.038512, 0.036, 0.0078214, 0.94121, 0.89692, 0.94946, 0.54232, 0.035271, 0.027604, 0.0020984, 0.0088442, 0.0088442, 0.0088442
|
|
||||||
72, 0.041711, 0.035849, 0.0077841, 0.94633, 0.90146, 0.94532, 0.55551, 0.034369, 0.028245, 0.0028688, 0.0088124, 0.0088124, 0.0088124
|
|
||||||
73, 0.043422, 0.034141, 0.008423, 0.89791, 0.79773, 0.89551, 0.49783, 0.036391, 0.032343, 0.0036569, 0.0087804, 0.0087804, 0.0087804
|
|
||||||
74, 0.041125, 0.034275, 0.0088747, 0.94643, 0.86711, 0.9366, 0.54438, 0.031141, 0.029405, 0.0027034, 0.0087479, 0.0087479, 0.0087479
|
|
||||||
75, 0.039719, 0.034131, 0.0079598, 0.9524, 0.91862, 0.9582, 0.59485, 0.03173, 0.026338, 0.0019864, 0.0087151, 0.0087151, 0.0087151
|
|
||||||
76, 0.040181, 0.033154, 0.0080667, 0.90734, 0.83848, 0.92208, 0.47094, 0.038296, 0.031134, 0.0040538, 0.008682, 0.008682, 0.008682
|
|
||||||
77, 0.03966, 0.033198, 0.0066327, 0.94442, 0.86113, 0.92597, 0.45845, 0.035619, 0.028766, 0.0026854, 0.0086485, 0.0086485, 0.0086485
|
|
||||||
78, 0.038331, 0.034961, 0.0069487, 0.91974, 0.89982, 0.94746, 0.51601, 0.034682, 0.02985, 0.0028031, 0.0086146, 0.0086146, 0.0086146
|
|
||||||
79, 0.038131, 0.034181, 0.0070184, 0.9505, 0.92209, 0.95505, 0.56273, 0.031882, 0.030202, 0.0025396, 0.0085805, 0.0085805, 0.0085805
|
|
||||||
80, 0.037099, 0.033424, 0.0061094, 0.95886, 0.9318, 0.94569, 0.56409, 0.031647, 0.027277, 0.0028533, 0.0085459, 0.0085459, 0.0085459
|
|
||||||
81, 0.038213, 0.035, 0.0062455, 0.90117, 0.91763, 0.93225, 0.58747, 0.030732, 0.026239, 0.0024431, 0.0085111, 0.0085111, 0.0085111
|
|
||||||
82, 0.038884, 0.031852, 0.0060274, 0.94817, 0.92094, 0.95121, 0.55533, 0.031829, 0.026745, 0.0023725, 0.0084759, 0.0084759, 0.0084759
|
|
||||||
83, 0.036625, 0.033138, 0.0079261, 0.95916, 0.91625, 0.94151, 0.5457, 0.034776, 0.026776, 0.0021613, 0.0084404, 0.0084404, 0.0084404
|
|
||||||
84, 0.038809, 0.032023, 0.0062357, 0.93504, 0.92504, 0.95141, 0.58087, 0.033784, 0.026052, 0.0023802, 0.0084046, 0.0084046, 0.0084046
|
|
||||||
85, 0.037893, 0.034964, 0.0068261, 0.92978, 0.93218, 0.95634, 0.58927, 0.031465, 0.026274, 0.0021452, 0.0083684, 0.0083684, 0.0083684
|
|
||||||
86, 0.038298, 0.033131, 0.0060222, 0.94402, 0.95637, 0.96109, 0.55015, 0.033578, 0.028523, 0.002081, 0.0083319, 0.0083319, 0.0083319
|
|
||||||
87, 0.037152, 0.034427, 0.0058415, 0.93586, 0.91752, 0.94697, 0.59167, 0.030662, 0.027937, 0.0022087, 0.0082952, 0.0082952, 0.0082952
|
|
||||||
88, 0.033444, 0.033919, 0.0065007, 0.97881, 0.93894, 0.95851, 0.60322, 0.031015, 0.025488, 0.0023777, 0.0082581, 0.0082581, 0.0082581
|
|
||||||
89, 0.034102, 0.033245, 0.006238, 0.97284, 0.92101, 0.95236, 0.58836, 0.031254, 0.026429, 0.0026268, 0.0082207, 0.0082207, 0.0082207
|
|
||||||
90, 0.033522, 0.03244, 0.0050727, 0.96762, 0.87823, 0.94835, 0.59588, 0.029, 0.026984, 0.003767, 0.008183, 0.008183, 0.008183
|
|
||||||
91, 0.034385, 0.03257, 0.0068179, 0.96143, 0.94048, 0.96293, 0.61393, 0.032598, 0.025748, 0.0025069, 0.008145, 0.008145, 0.008145
|
|
||||||
92, 0.038411, 0.03149, 0.008301, 0.85757, 0.82488, 0.90553, 0.50806, 0.03392, 0.030222, 0.0066837, 0.0081068, 0.0081068, 0.0081068
|
|
||||||
93, 0.038098, 0.030603, 0.0062063, 0.87368, 0.83447, 0.8986, 0.48715, 0.032855, 0.030639, 0.0038948, 0.0080682, 0.0080682, 0.0080682
|
|
||||||
94, 0.038408, 0.031401, 0.0071762, 0.97569, 0.88239, 0.94377, 0.57059, 0.032335, 0.027143, 0.0022352, 0.0080294, 0.0080294, 0.0080294
|
|
||||||
95, 0.037455, 0.031985, 0.0056255, 0.92462, 0.91911, 0.95528, 0.57158, 0.032933, 0.02751, 0.0028774, 0.0079903, 0.0079903, 0.0079903
|
|
||||||
96, 0.034081, 0.032974, 0.0055842, 0.95494, 0.95877, 0.96191, 0.56896, 0.031626, 0.02607, 0.0021001, 0.0079509, 0.0079509, 0.0079509
|
|
||||||
97, 0.036189, 0.031882, 0.0066565, 0.95704, 0.92485, 0.96058, 0.61761, 0.031169, 0.024964, 0.0026779, 0.0079112, 0.0079112, 0.0079112
|
|
||||||
98, 0.034716, 0.033089, 0.0062765, 0.95208, 0.9259, 0.95999, 0.58112, 0.031563, 0.025833, 0.002693, 0.0078713, 0.0078713, 0.0078713
|
|
||||||
99, 0.035807, 0.032488, 0.0062112, 0.94346, 0.93805, 0.95484, 0.58984, 0.030902, 0.025948, 0.0019203, 0.0078311, 0.0078311, 0.0078311
|
|
||||||
100, 0.035404, 0.030942, 0.0070651, 0.90669, 0.90848, 0.94371, 0.55885, 0.032847, 0.031035, 0.0054341, 0.0077907, 0.0077907, 0.0077907
|
|
||||||
101, 0.034805, 0.032716, 0.007314, 0.95797, 0.95318, 0.96146, 0.57165, 0.031743, 0.027374, 0.0019765, 0.00775, 0.00775, 0.00775
|
|
||||||
102, 0.036556, 0.032288, 0.0068758, 0.93197, 0.95396, 0.96154, 0.58878, 0.030179, 0.028715, 0.0022038, 0.0077091, 0.0077091, 0.0077091
|
|
||||||
103, 0.034745, 0.03311, 0.0060098, 0.91789, 0.95751, 0.9557, 0.60553, 0.030048, 0.028515, 0.0018339, 0.0076679, 0.0076679, 0.0076679
|
|
||||||
104, 0.035191, 0.032241, 0.0060717, 0.89044, 0.92859, 0.9459, 0.55454, 0.031789, 0.029479, 0.0041273, 0.0076265, 0.0076265, 0.0076265
|
|
||||||
105, 0.035232, 0.030591, 0.0058525, 0.88359, 0.89753, 0.93313, 0.58269, 0.030801, 0.027946, 0.0030299, 0.0075848, 0.0075848, 0.0075848
|
|
||||||
106, 0.034891, 0.031808, 0.0054986, 0.92895, 0.85635, 0.92882, 0.49609, 0.034223, 0.029069, 0.0034086, 0.007543, 0.007543, 0.007543
|
|
||||||
107, 0.034206, 0.032183, 0.0059379, 0.95328, 0.90682, 0.95609, 0.5899, 0.032747, 0.02519, 0.002409, 0.0075009, 0.0075009, 0.0075009
|
|
||||||
108, 0.035193, 0.032691, 0.006186, 0.76003, 0.88884, 0.92562, 0.52785, 0.033637, 0.027941, 0.0085591, 0.0074585, 0.0074585, 0.0074585
|
|
||||||
109, 0.032678, 0.031774, 0.0051808, 0.9394, 0.94668, 0.95971, 0.59036, 0.029259, 0.025816, 0.0018039, 0.007416, 0.007416, 0.007416
|
|
||||||
110, 0.034928, 0.032253, 0.0052045, 0.96947, 0.9156, 0.95994, 0.57839, 0.031965, 0.025841, 0.0017381, 0.0073733, 0.0073733, 0.0073733
|
|
||||||
111, 0.032909, 0.030654, 0.0068091, 0.93353, 0.9431, 0.95796, 0.6155, 0.029402, 0.024355, 0.00166, 0.0073303, 0.0073303, 0.0073303
|
|
||||||
112, 0.034421, 0.030596, 0.0056472, 0.97009, 0.96553, 0.96802, 0.62231, 0.027934, 0.024545, 0.0017626, 0.0072872, 0.0072872, 0.0072872
|
|
||||||
113, 0.033877, 0.031202, 0.0048802, 0.96084, 0.94522, 0.95601, 0.59425, 0.029266, 0.025481, 0.0019383, 0.0072438, 0.0072438, 0.0072438
|
|
||||||
114, 0.032888, 0.030615, 0.0059414, 0.96707, 0.96629, 0.96299, 0.58985, 0.028752, 0.02581, 0.001971, 0.0072003, 0.0072003, 0.0072003
|
|
||||||
115, 0.033697, 0.032449, 0.0059314, 0.98178, 0.96195, 0.96413, 0.62237, 0.030004, 0.025665, 0.0022348, 0.0071566, 0.0071566, 0.0071566
|
|
||||||
116, 0.032169, 0.028243, 0.0053777, 0.96855, 0.95665, 0.96663, 0.59072, 0.030777, 0.027957, 0.0025654, 0.0071127, 0.0071127, 0.0071127
|
|
||||||
117, 0.031322, 0.029406, 0.0044561, 0.95818, 0.95873, 0.96789, 0.61904, 0.03089, 0.02532, 0.0023165, 0.0070686, 0.0070686, 0.0070686
|
|
||||||
118, 0.032621, 0.031882, 0.0060545, 0.96766, 0.9703, 0.97043, 0.61416, 0.031658, 0.02589, 0.0024626, 0.0070243, 0.0070243, 0.0070243
|
|
||||||
119, 0.033223, 0.027714, 0.0065067, 0.98299, 0.96548, 0.96768, 0.62695, 0.029253, 0.02492, 0.0019283, 0.0069799, 0.0069799, 0.0069799
|
|
||||||
120, 0.033553, 0.029447, 0.0063224, 0.98701, 0.95656, 0.96794, 0.64578, 0.027592, 0.02491, 0.0018422, 0.0069353, 0.0069353, 0.0069353
|
|
||||||
121, 0.03325, 0.028541, 0.0051204, 0.98317, 0.93651, 0.96604, 0.61816, 0.032385, 0.023813, 0.0019208, 0.0068906, 0.0068906, 0.0068906
|
|
||||||
122, 0.033097, 0.02979, 0.0057041, 0.97144, 0.93651, 0.96183, 0.61828, 0.027016, 0.026034, 0.0019498, 0.0068457, 0.0068457, 0.0068457
|
|
||||||
123, 0.032385, 0.031679, 0.0052411, 0.97262, 0.94493, 0.96298, 0.62283, 0.026364, 0.025603, 0.0019448, 0.0068006, 0.0068006, 0.0068006
|
|
||||||
124, 0.033781, 0.029724, 0.0050386, 0.95657, 0.95188, 0.96177, 0.64612, 0.028362, 0.024317, 0.0019741, 0.0067555, 0.0067555, 0.0067555
|
|
||||||
125, 0.032106, 0.029237, 0.0045665, 0.94958, 0.9452, 0.96075, 0.64017, 0.028601, 0.024065, 0.0021955, 0.0067101, 0.0067101, 0.0067101
|
|
||||||
126, 0.032264, 0.029086, 0.0054842, 0.95887, 0.96354, 0.96768, 0.66344, 0.026937, 0.023887, 0.0024299, 0.0066647, 0.0066647, 0.0066647
|
|
||||||
127, 0.032503, 0.030248, 0.0055057, 0.96337, 0.96553, 0.96908, 0.6688, 0.026015, 0.023054, 0.002129, 0.0066191, 0.0066191, 0.0066191
|
|
||||||
128, 0.031848, 0.030237, 0.0040163, 0.97874, 0.9667, 0.96928, 0.65926, 0.026758, 0.024459, 0.0019228, 0.0065734, 0.0065734, 0.0065734
|
|
||||||
129, 0.033826, 0.03026, 0.0075954, 0.97185, 0.97532, 0.97586, 0.65575, 0.027961, 0.023636, 0.0018942, 0.0065276, 0.0065276, 0.0065276
|
|
||||||
130, 0.034133, 0.029008, 0.0056355, 0.98736, 0.94112, 0.9718, 0.63606, 0.02707, 0.024257, 0.0019156, 0.0064816, 0.0064816, 0.0064816
|
|
||||||
131, 0.032031, 0.029106, 0.0046239, 0.97221, 0.91833, 0.96514, 0.62362, 0.027138, 0.024794, 0.0020008, 0.0064356, 0.0064356, 0.0064356
|
|
||||||
132, 0.031064, 0.028333, 0.005266, 0.90643, 0.90848, 0.94398, 0.52023, 0.032159, 0.02668, 0.0031502, 0.0063895, 0.0063895, 0.0063895
|
|
||||||
133, 0.031294, 0.030179, 0.0047473, 0.9751, 0.94523, 0.96989, 0.60873, 0.028775, 0.024644, 0.0019185, 0.0063432, 0.0063432, 0.0063432
|
|
||||||
134, 0.03095, 0.029861, 0.004757, 0.93719, 0.96354, 0.96023, 0.64725, 0.026088, 0.024737, 0.001847, 0.0062969, 0.0062969, 0.0062969
|
|
||||||
135, 0.030516, 0.028845, 0.0047947, 0.95301, 0.95197, 0.96786, 0.62838, 0.026574, 0.024545, 0.0017698, 0.0062505, 0.0062505, 0.0062505
|
|
||||||
136, 0.030475, 0.02846, 0.0055107, 0.96437, 0.9451, 0.96404, 0.64108, 0.027123, 0.024913, 0.0017149, 0.006204, 0.006204, 0.006204
|
|
||||||
137, 0.030362, 0.029429, 0.0048351, 0.97425, 0.96309, 0.96501, 0.6316, 0.027754, 0.025372, 0.0018266, 0.0061574, 0.0061574, 0.0061574
|
|
||||||
138, 0.030377, 0.030139, 0.0047596, 0.96266, 0.96512, 0.96441, 0.63686, 0.027537, 0.024936, 0.0019117, 0.0061107, 0.0061107, 0.0061107
|
|
||||||
139, 0.030934, 0.027383, 0.0046041, 0.97265, 0.9703, 0.96765, 0.64827, 0.027235, 0.024562, 0.0018573, 0.006064, 0.006064, 0.006064
|
|
||||||
140, 0.030503, 0.030103, 0.005123, 0.96566, 0.95537, 0.96187, 0.62706, 0.027453, 0.024727, 0.0018926, 0.0060172, 0.0060172, 0.0060172
|
|
||||||
141, 0.031252, 0.028443, 0.0041605, 0.97251, 0.96352, 0.96748, 0.66484, 0.026909, 0.024105, 0.0020043, 0.0059704, 0.0059704, 0.0059704
|
|
||||||
142, 0.029091, 0.029802, 0.004882, 0.98107, 0.97705, 0.97517, 0.6692, 0.025419, 0.023475, 0.0019698, 0.0059235, 0.0059235, 0.0059235
|
|
||||||
143, 0.029031, 0.027532, 0.0044102, 0.96415, 0.95001, 0.96306, 0.65746, 0.026583, 0.024414, 0.0018636, 0.0058766, 0.0058766, 0.0058766
|
|
||||||
144, 0.030322, 0.029805, 0.0045858, 0.95213, 0.97029, 0.96608, 0.66087, 0.02622, 0.024185, 0.0019045, 0.0058296, 0.0058296, 0.0058296
|
|
||||||
145, 0.03003, 0.027735, 0.0042047, 0.9629, 0.97049, 0.97254, 0.6706, 0.025957, 0.023952, 0.0019944, 0.0057826, 0.0057826, 0.0057826
|
|
||||||
146, 0.030178, 0.028212, 0.0038413, 0.97726, 0.96369, 0.96698, 0.6622, 0.025378, 0.025052, 0.0019726, 0.0057355, 0.0057355, 0.0057355
|
|
||||||
147, 0.0287, 0.027819, 0.0042913, 0.97216, 0.96354, 0.96631, 0.64059, 0.025874, 0.024205, 0.0019755, 0.0056884, 0.0056884, 0.0056884
|
|
||||||
148, 0.032043, 0.027684, 0.0048876, 0.98775, 0.95678, 0.96185, 0.61574, 0.029168, 0.025582, 0.001935, 0.0056413, 0.0056413, 0.0056413
|
|
||||||
149, 0.030177, 0.027118, 0.0045694, 0.98348, 0.95001, 0.96349, 0.66463, 0.026593, 0.023216, 0.0019195, 0.0055942, 0.0055942, 0.0055942
|
|
||||||
150, 0.028507, 0.030105, 0.0049029, 0.98161, 0.95661, 0.96846, 0.65684, 0.02566, 0.023492, 0.0021502, 0.0055471, 0.0055471, 0.0055471
|
|
||||||
151, 0.030499, 0.028858, 0.0074011, 0.98125, 0.9703, 0.97297, 0.68484, 0.026201, 0.022504, 0.002315, 0.0055, 0.0055, 0.0055
|
|
||||||
152, 0.02793, 0.028107, 0.0056783, 0.98268, 0.95669, 0.96742, 0.68158, 0.026543, 0.023369, 0.0024157, 0.0054529, 0.0054529, 0.0054529
|
|
||||||
153, 0.028745, 0.027211, 0.0047151, 0.98282, 0.95678, 0.96778, 0.67643, 0.024136, 0.022676, 0.0020738, 0.0054058, 0.0054058, 0.0054058
|
|
||||||
154, 0.02988, 0.028095, 0.0047024, 0.97564, 0.95678, 0.96446, 0.67542, 0.026337, 0.02249, 0.002291, 0.0053587, 0.0053587, 0.0053587
|
|
||||||
155, 0.028457, 0.029243, 0.0047708, 0.96159, 0.95678, 0.95796, 0.66082, 0.026913, 0.022992, 0.0021378, 0.0053116, 0.0053116, 0.0053116
|
|
||||||
156, 0.028992, 0.027253, 0.0048825, 0.97888, 0.96996, 0.9719, 0.6495, 0.027016, 0.022958, 0.001994, 0.0052645, 0.0052645, 0.0052645
|
|
||||||
157, 0.028998, 0.028506, 0.0044686, 0.95299, 0.97018, 0.96508, 0.6518, 0.026524, 0.022246, 0.0018938, 0.0052174, 0.0052174, 0.0052174
|
|
||||||
158, 0.029876, 0.028789, 0.0045456, 0.97905, 0.9703, 0.96656, 0.67184, 0.026013, 0.023414, 0.0020316, 0.0051704, 0.0051704, 0.0051704
|
|
||||||
159, 0.02783, 0.027954, 0.0047788, 0.95981, 0.9703, 0.97331, 0.65536, 0.026615, 0.023393, 0.0021369, 0.0051234, 0.0051234, 0.0051234
|
|
||||||
160, 0.02881, 0.029834, 0.0051372, 0.96231, 0.97705, 0.97276, 0.67234, 0.02516, 0.023334, 0.0020906, 0.0050765, 0.0050765, 0.0050765
|
|
||||||
161, 0.02907, 0.028024, 0.0050542, 0.97128, 0.97694, 0.97459, 0.67987, 0.024301, 0.022933, 0.0018993, 0.0050296, 0.0050296, 0.0050296
|
|
||||||
162, 0.027088, 0.02831, 0.0049067, 0.97555, 0.97705, 0.97511, 0.68172, 0.02416, 0.022443, 0.0016887, 0.0049828, 0.0049828, 0.0049828
|
|
||||||
163, 0.030222, 0.026841, 0.004733, 0.97753, 0.97705, 0.97482, 0.68213, 0.025884, 0.02258, 0.0016608, 0.004936, 0.004936, 0.004936
|
|
||||||
164, 0.028023, 0.028466, 0.0040835, 0.95802, 0.94365, 0.96412, 0.68017, 0.027131, 0.022298, 0.0018087, 0.0048893, 0.0048893, 0.0048893
|
|
||||||
165, 0.028881, 0.028552, 0.0037733, 0.98463, 0.9703, 0.966, 0.69216, 0.024287, 0.022506, 0.0017584, 0.0048426, 0.0048426, 0.0048426
|
|
||||||
166, 0.02887, 0.028066, 0.0051819, 0.97967, 0.97023, 0.96605, 0.67742, 0.023991, 0.022966, 0.0017765, 0.004796, 0.004796, 0.004796
|
|
||||||
167, 0.027769, 0.027876, 0.0045376, 0.97336, 0.9703, 0.96585, 0.67378, 0.024131, 0.022832, 0.0018437, 0.0047495, 0.0047495, 0.0047495
|
|
||||||
168, 0.026105, 0.026978, 0.0043823, 0.98068, 0.9703, 0.97141, 0.68531, 0.02506, 0.022971, 0.0019168, 0.0047031, 0.0047031, 0.0047031
|
|
||||||
169, 0.027398, 0.02762, 0.0039622, 0.98055, 0.96775, 0.96652, 0.69533, 0.023761, 0.022578, 0.0018546, 0.0046568, 0.0046568, 0.0046568
|
|
||||||
170, 0.028034, 0.027971, 0.0037273, 0.97684, 0.9703, 0.96783, 0.69053, 0.023457, 0.0223, 0.0017781, 0.0046105, 0.0046105, 0.0046105
|
|
||||||
171, 0.027347, 0.028535, 0.0038968, 0.97337, 0.96354, 0.96296, 0.67883, 0.024073, 0.022644, 0.001817, 0.0045644, 0.0045644, 0.0045644
|
|
||||||
172, 0.028142, 0.026267, 0.0034699, 0.98644, 0.96343, 0.96703, 0.69874, 0.02388, 0.02208, 0.0017773, 0.0045184, 0.0045184, 0.0045184
|
|
||||||
173, 0.026171, 0.027753, 0.0050813, 0.97569, 0.96352, 0.96478, 0.67178, 0.02579, 0.022882, 0.0018091, 0.0044724, 0.0044724, 0.0044724
|
|
||||||
174, 0.026128, 0.026436, 0.0053865, 0.97295, 0.96346, 0.96565, 0.67965, 0.025346, 0.023009, 0.001846, 0.0044266, 0.0044266, 0.0044266
|
|
||||||
175, 0.02726, 0.027188, 0.0035265, 0.97704, 0.96351, 0.96655, 0.68568, 0.024316, 0.022898, 0.0017214, 0.0043809, 0.0043809, 0.0043809
|
|
||||||
176, 0.026716, 0.026838, 0.0031932, 0.98022, 0.96354, 0.96597, 0.68301, 0.025983, 0.023226, 0.0016424, 0.0043353, 0.0043353, 0.0043353
|
|
||||||
177, 0.027251, 0.028037, 0.0054986, 0.97271, 0.96354, 0.96646, 0.68557, 0.026387, 0.022748, 0.0016146, 0.0042899, 0.0042899, 0.0042899
|
|
||||||
178, 0.026909, 0.026743, 0.0046035, 0.98252, 0.97027, 0.97551, 0.66755, 0.026705, 0.022883, 0.0016144, 0.0042445, 0.0042445, 0.0042445
|
|
||||||
179, 0.026095, 0.026161, 0.0058214, 0.98155, 0.97028, 0.96818, 0.66911, 0.025493, 0.023625, 0.0016812, 0.0041994, 0.0041994, 0.0041994
|
|
||||||
180, 0.024472, 0.026628, 0.0041876, 0.98266, 0.97705, 0.97576, 0.66959, 0.024833, 0.022997, 0.0017462, 0.0041543, 0.0041543, 0.0041543
|
|
||||||
181, 0.027072, 0.027344, 0.0044676, 0.98132, 0.97705, 0.9754, 0.68045, 0.024837, 0.022527, 0.0017458, 0.0041094, 0.0041094, 0.0041094
|
|
||||||
182, 0.028166, 0.02681, 0.0042947, 0.98137, 0.9703, 0.9683, 0.68976, 0.024242, 0.022963, 0.001793, 0.0040647, 0.0040647, 0.0040647
|
|
||||||
183, 0.026102, 0.027943, 0.0043331, 0.95813, 0.97705, 0.97464, 0.69977, 0.023437, 0.022746, 0.0018653, 0.0040201, 0.0040201, 0.0040201
|
|
||||||
184, 0.026373, 0.026178, 0.0037455, 0.98558, 0.96354, 0.97444, 0.69813, 0.024044, 0.022799, 0.0018616, 0.0039757, 0.0039757, 0.0039757
|
|
||||||
185, 0.028673, 0.026108, 0.0044021, 0.98181, 0.95199, 0.96343, 0.67845, 0.024732, 0.023188, 0.0018667, 0.0039314, 0.0039314, 0.0039314
|
|
||||||
186, 0.026675, 0.02758, 0.0041627, 0.98565, 0.96353, 0.96589, 0.68148, 0.022764, 0.022821, 0.001741, 0.0038873, 0.0038873, 0.0038873
|
|
||||||
187, 0.026643, 0.027148, 0.0038995, 0.98353, 0.97028, 0.96679, 0.68438, 0.02252, 0.022897, 0.0017302, 0.0038434, 0.0038434, 0.0038434
|
|
||||||
188, 0.027608, 0.027644, 0.0039359, 0.98275, 0.977, 0.97892, 0.69636, 0.023269, 0.022497, 0.0018708, 0.0037997, 0.0037997, 0.0037997
|
|
||||||
189, 0.024131, 0.027909, 0.0027875, 0.97406, 0.9703, 0.97597, 0.69888, 0.023948, 0.022371, 0.0023066, 0.0037562, 0.0037562, 0.0037562
|
|
||||||
190, 0.027156, 0.027026, 0.0036558, 0.98347, 0.96347, 0.9715, 0.68745, 0.023983, 0.023429, 0.0027685, 0.0037128, 0.0037128, 0.0037128
|
|
||||||
191, 0.027734, 0.026852, 0.0039689, 0.97298, 0.97025, 0.9738, 0.6853, 0.026086, 0.022382, 0.0022475, 0.0036697, 0.0036697, 0.0036697
|
|
||||||
192, 0.026927, 0.026752, 0.0037148, 0.96858, 0.96354, 0.96962, 0.69858, 0.023535, 0.022065, 0.0017252, 0.0036267, 0.0036267, 0.0036267
|
|
||||||
193, 0.027003, 0.027176, 0.0053776, 0.96122, 0.97705, 0.97883, 0.66762, 0.023695, 0.022581, 0.0018148, 0.003584, 0.003584, 0.003584
|
|
||||||
194, 0.026989, 0.027615, 0.006495, 0.95862, 0.95678, 0.96378, 0.61374, 0.02806, 0.024838, 0.0017687, 0.0035415, 0.0035415, 0.0035415
|
|
||||||
195, 0.027666, 0.026871, 0.0057181, 0.96489, 0.9702, 0.96448, 0.66116, 0.024083, 0.024089, 0.0018062, 0.0034991, 0.0034991, 0.0034991
|
|
||||||
196, 0.026176, 0.02691, 0.004667, 0.97361, 0.96348, 0.96482, 0.67681, 0.024865, 0.023765, 0.0019973, 0.003457, 0.003457, 0.003457
|
|
||||||
197, 0.026469, 0.027627, 0.0049022, 0.96453, 0.96354, 0.97173, 0.68511, 0.024681, 0.022624, 0.0021242, 0.0034152, 0.0034152, 0.0034152
|
|
||||||
198, 0.027208, 0.028003, 0.0049884, 0.97647, 0.96354, 0.96577, 0.69568, 0.024119, 0.022065, 0.0021831, 0.0033735, 0.0033735, 0.0033735
|
|
||||||
199, 0.025903, 0.027341, 0.0048099, 0.98137, 0.95876, 0.96996, 0.69246, 0.024701, 0.022356, 0.0023582, 0.0033321, 0.0033321, 0.0033321
|
|
||||||
200, 0.026184, 0.027374, 0.0042712, 0.98338, 0.9635, 0.96994, 0.67492, 0.025071, 0.022943, 0.0024592, 0.0032909, 0.0032909, 0.0032909
|
|
||||||
201, 0.026189, 0.025554, 0.0040891, 0.98737, 0.94994, 0.96182, 0.66253, 0.025125, 0.023302, 0.0023766, 0.00325, 0.00325, 0.00325
|
|
||||||
202, 0.024545, 0.026731, 0.0041204, 0.9815, 0.9703, 0.97592, 0.68519, 0.024929, 0.022513, 0.0020454, 0.0032093, 0.0032093, 0.0032093
|
|
||||||
203, 0.02617, 0.025825, 0.0042871, 0.95509, 0.97705, 0.97726, 0.68377, 0.024432, 0.022358, 0.0020345, 0.0031689, 0.0031689, 0.0031689
|
|
||||||
204, 0.023137, 0.024813, 0.0036278, 0.96776, 0.96354, 0.97128, 0.69433, 0.026057, 0.022551, 0.0019471, 0.0031287, 0.0031287, 0.0031287
|
|
||||||
205, 0.025338, 0.025502, 0.0037127, 0.99338, 0.95089, 0.96514, 0.68198, 0.025945, 0.023259, 0.0021286, 0.0030888, 0.0030888, 0.0030888
|
|
||||||
206, 0.026339, 0.02602, 0.0039489, 0.98518, 0.97028, 0.96743, 0.67505, 0.023719, 0.022723, 0.0020737, 0.0030491, 0.0030491, 0.0030491
|
|
||||||
207, 0.026491, 0.027071, 0.0040128, 0.98605, 0.96354, 0.96766, 0.68313, 0.024904, 0.022284, 0.0022663, 0.0030097, 0.0030097, 0.0030097
|
|
||||||
208, 0.025094, 0.025137, 0.0043872, 0.99331, 0.9505, 0.96795, 0.6957, 0.024963, 0.021901, 0.0026323, 0.0029706, 0.0029706, 0.0029706
|
|
||||||
209, 0.026184, 0.027171, 0.0039022, 0.9868, 0.95678, 0.96685, 0.69064, 0.026298, 0.022596, 0.0027955, 0.0029318, 0.0029318, 0.0029318
|
|
||||||
210, 0.025956, 0.025668, 0.0049788, 0.97688, 0.95678, 0.97237, 0.69002, 0.025732, 0.022511, 0.0025778, 0.0028932, 0.0028932, 0.0028932
|
|
||||||
211, 0.027297, 0.025791, 0.0040839, 0.98462, 0.9703, 0.96931, 0.6969, 0.026088, 0.0223, 0.0022371, 0.002855, 0.002855, 0.002855
|
|
||||||
212, 0.02525, 0.026303, 0.0047559, 0.9774, 0.96349, 0.96719, 0.69013, 0.025161, 0.022704, 0.0021132, 0.002817, 0.002817, 0.002817
|
|
||||||
213, 0.024295, 0.026973, 0.0041341, 0.97281, 0.97705, 0.9826, 0.68997, 0.024569, 0.022605, 0.0019869, 0.0027793, 0.0027793, 0.0027793
|
|
||||||
214, 0.024136, 0.025274, 0.0038694, 0.97589, 0.94326, 0.97578, 0.68725, 0.02548, 0.022043, 0.0018324, 0.0027419, 0.0027419, 0.0027419
|
|
||||||
215, 0.025528, 0.027067, 0.0040959, 0.96603, 0.9567, 0.96499, 0.68876, 0.024627, 0.022841, 0.0020294, 0.0027048, 0.0027048, 0.0027048
|
|
||||||
216, 0.025221, 0.027184, 0.0047706, 0.95868, 0.96353, 0.96453, 0.6809, 0.025527, 0.022776, 0.0021757, 0.0026681, 0.0026681, 0.0026681
|
|
||||||
217, 0.024044, 0.024836, 0.0042798, 0.98084, 0.95673, 0.96482, 0.68198, 0.025761, 0.022618, 0.002021, 0.0026316, 0.0026316, 0.0026316
|
|
||||||
218, 0.025253, 0.027373, 0.0041113, 0.96325, 0.9689, 0.97805, 0.69718, 0.025244, 0.021851, 0.0018038, 0.0025954, 0.0025954, 0.0025954
|
|
||||||
219, 0.025786, 0.024412, 0.0038547, 0.9784, 0.96354, 0.97334, 0.67628, 0.024993, 0.022038, 0.001677, 0.0025596, 0.0025596, 0.0025596
|
|
||||||
220, 0.024866, 0.025262, 0.0039628, 0.97738, 0.96354, 0.97295, 0.67586, 0.025099, 0.02182, 0.0016662, 0.0025241, 0.0025241, 0.0025241
|
|
||||||
221, 0.025464, 0.027381, 0.0037889, 0.95635, 0.97015, 0.96925, 0.70037, 0.024523, 0.021997, 0.0017885, 0.0024889, 0.0024889, 0.0024889
|
|
||||||
222, 0.024976, 0.025851, 0.0034427, 0.95665, 0.96354, 0.96272, 0.70145, 0.024242, 0.021824, 0.0018279, 0.0024541, 0.0024541, 0.0024541
|
|
||||||
223, 0.024802, 0.02694, 0.0031541, 0.95601, 0.96294, 0.9618, 0.68561, 0.024934, 0.022417, 0.0018971, 0.0024195, 0.0024195, 0.0024195
|
|
||||||
224, 0.024682, 0.026038, 0.0032441, 0.97713, 0.96354, 0.97524, 0.68246, 0.026721, 0.022906, 0.0020948, 0.0023854, 0.0023854, 0.0023854
|
|
||||||
225, 0.025083, 0.026697, 0.0037998, 0.96721, 0.9703, 0.97428, 0.68679, 0.02599, 0.022761, 0.0020577, 0.0023515, 0.0023515, 0.0023515
|
|
||||||
226, 0.024088, 0.025932, 0.0035885, 0.96876, 0.97703, 0.97508, 0.68276, 0.024445, 0.022962, 0.0019322, 0.002318, 0.002318, 0.002318
|
|
||||||
227, 0.023332, 0.025505, 0.0037625, 0.96578, 0.97705, 0.97358, 0.68462, 0.024101, 0.02255, 0.0018148, 0.0022849, 0.0022849, 0.0022849
|
|
||||||
228, 0.024702, 0.024819, 0.0034758, 0.97385, 0.97028, 0.97462, 0.69212, 0.024558, 0.022178, 0.0017297, 0.0022521, 0.0022521, 0.0022521
|
|
||||||
229, 0.024602, 0.025566, 0.0038347, 0.96628, 0.96353, 0.96616, 0.70351, 0.023898, 0.022227, 0.0016842, 0.0022196, 0.0022196, 0.0022196
|
|
||||||
230, 0.023372, 0.025582, 0.0035108, 0.98707, 0.9567, 0.96796, 0.6879, 0.024704, 0.022368, 0.0017089, 0.0021876, 0.0021876, 0.0021876
|
|
||||||
231, 0.024074, 0.025893, 0.0031354, 0.98694, 0.95678, 0.9676, 0.68024, 0.024659, 0.023358, 0.0017729, 0.0021558, 0.0021558, 0.0021558
|
|
||||||
232, 0.024966, 0.027324, 0.0032754, 0.9826, 0.95678, 0.9736, 0.70037, 0.02362, 0.022499, 0.001837, 0.0021245, 0.0021245, 0.0021245
|
|
||||||
233, 0.025124, 0.026055, 0.0039871, 0.9706, 0.96971, 0.97903, 0.70731, 0.0229, 0.021873, 0.0017568, 0.0020935, 0.0020935, 0.0020935
|
|
||||||
234, 0.022206, 0.02586, 0.0033446, 0.9787, 0.95003, 0.96954, 0.70051, 0.023775, 0.022511, 0.0017292, 0.0020629, 0.0020629, 0.0020629
|
|
||||||
235, 0.024355, 0.023389, 0.0040127, 0.98374, 0.9703, 0.96776, 0.68733, 0.022898, 0.022383, 0.0017637, 0.0020327, 0.0020327, 0.0020327
|
|
||||||
236, 0.024096, 0.026566, 0.0032116, 0.98492, 0.96354, 0.97267, 0.70113, 0.021918, 0.022037, 0.0017403, 0.0020028, 0.0020028, 0.0020028
|
|
||||||
237, 0.024077, 0.025841, 0.0032894, 0.97582, 0.96353, 0.967, 0.69301, 0.021952, 0.02197, 0.0017976, 0.0019734, 0.0019734, 0.0019734
|
|
||||||
238, 0.024347, 0.025564, 0.0039452, 0.97899, 0.96354, 0.96707, 0.69185, 0.022981, 0.022335, 0.0018357, 0.0019443, 0.0019443, 0.0019443
|
|
||||||
239, 0.023853, 0.024579, 0.0044756, 0.97532, 0.95678, 0.96534, 0.69215, 0.023931, 0.022646, 0.0018563, 0.0019156, 0.0019156, 0.0019156
|
|
||||||
240, 0.023002, 0.025647, 0.0035852, 0.97411, 0.96353, 0.97209, 0.69136, 0.023933, 0.022786, 0.0019303, 0.0018873, 0.0018873, 0.0018873
|
|
||||||
241, 0.023632, 0.025356, 0.0034878, 0.96367, 0.97026, 0.98007, 0.70663, 0.023831, 0.022384, 0.0019032, 0.0018594, 0.0018594, 0.0018594
|
|
||||||
242, 0.023527, 0.025798, 0.0036633, 0.97056, 0.96832, 0.97529, 0.70001, 0.024231, 0.022414, 0.001796, 0.0018319, 0.0018319, 0.0018319
|
|
||||||
243, 0.022682, 0.025564, 0.003487, 0.97515, 0.96351, 0.9668, 0.69187, 0.024127, 0.022944, 0.0017143, 0.0018048, 0.0018048, 0.0018048
|
|
||||||
244, 0.024222, 0.026106, 0.0035024, 0.97655, 0.95675, 0.96682, 0.69463, 0.023624, 0.022958, 0.0016919, 0.0017781, 0.0017781, 0.0017781
|
|
||||||
245, 0.02326, 0.025099, 0.0029967, 0.96808, 0.97681, 0.97562, 0.70458, 0.023273, 0.02276, 0.0016949, 0.0017519, 0.0017519, 0.0017519
|
|
||||||
246, 0.024062, 0.024739, 0.0040586, 0.96483, 0.9635, 0.97182, 0.69647, 0.023717, 0.022898, 0.0017371, 0.001726, 0.001726, 0.001726
|
|
||||||
247, 0.023201, 0.0253, 0.0032933, 0.97972, 0.95633, 0.97253, 0.69153, 0.024038, 0.022889, 0.0017084, 0.0017005, 0.0017005, 0.0017005
|
|
||||||
248, 0.024654, 0.026136, 0.0033753, 0.98866, 0.95667, 0.97459, 0.68796, 0.023902, 0.022352, 0.0017804, 0.0016755, 0.0016755, 0.0016755
|
|
||||||
249, 0.023838, 0.025222, 0.0033712, 0.96588, 0.9703, 0.97386, 0.69894, 0.023947, 0.022392, 0.0018015, 0.0016509, 0.0016509, 0.0016509
|
|
||||||
250, 0.023668, 0.024787, 0.0034169, 0.98732, 0.95003, 0.96765, 0.69254, 0.023956, 0.022749, 0.0017763, 0.0016267, 0.0016267, 0.0016267
|
|
||||||
251, 0.022859, 0.025103, 0.003568, 0.95814, 0.97702, 0.9737, 0.70092, 0.023604, 0.022479, 0.0017848, 0.0016029, 0.0016029, 0.0016029
|
|
||||||
252, 0.022666, 0.024463, 0.0032009, 0.98704, 0.97027, 0.97466, 0.69009, 0.023513, 0.022304, 0.0017728, 0.0015795, 0.0015795, 0.0015795
|
|
||||||
253, 0.023492, 0.026417, 0.0028279, 0.96436, 0.98372, 0.98019, 0.69935, 0.023358, 0.021836, 0.00174, 0.0015566, 0.0015566, 0.0015566
|
|
||||||
254, 0.024491, 0.025485, 0.002979, 0.9853, 0.95678, 0.96646, 0.69592, 0.023924, 0.022304, 0.0018352, 0.0015341, 0.0015341, 0.0015341
|
|
||||||
255, 0.02484, 0.025362, 0.0035361, 0.96452, 0.96353, 0.9651, 0.69518, 0.024445, 0.022635, 0.0018837, 0.0015121, 0.0015121, 0.0015121
|
|
||||||
256, 0.023908, 0.025521, 0.0036297, 0.96519, 0.96354, 0.96511, 0.6864, 0.024269, 0.022565, 0.0018298, 0.0014905, 0.0014905, 0.0014905
|
|
||||||
257, 0.02373, 0.025435, 0.0035398, 0.97944, 0.97703, 0.98018, 0.69367, 0.023299, 0.022476, 0.001668, 0.0014693, 0.0014693, 0.0014693
|
|
||||||
258, 0.023375, 0.025846, 0.0030582, 0.98528, 0.97531, 0.97812, 0.69421, 0.023276, 0.022128, 0.0015514, 0.0014486, 0.0014486, 0.0014486
|
|
||||||
259, 0.021545, 0.024249, 0.0026146, 0.97663, 0.97029, 0.97653, 0.71099, 0.023939, 0.022179, 0.0015795, 0.0014283, 0.0014283, 0.0014283
|
|
||||||
260, 0.022169, 0.025532, 0.0040977, 0.97732, 0.9703, 0.97464, 0.68688, 0.024342, 0.022362, 0.001622, 0.0014084, 0.0014084, 0.0014084
|
|
||||||
261, 0.022755, 0.024997, 0.0032319, 0.97619, 0.9703, 0.97406, 0.70667, 0.024472, 0.021516, 0.0016024, 0.001389, 0.001389, 0.001389
|
|
||||||
262, 0.023288, 0.02633, 0.0034072, 0.97402, 0.97705, 0.97597, 0.70608, 0.023844, 0.021676, 0.0016408, 0.0013701, 0.0013701, 0.0013701
|
|
||||||
263, 0.02379, 0.025776, 0.0036441, 0.97543, 0.98358, 0.98268, 0.70729, 0.024337, 0.022026, 0.0016763, 0.0013516, 0.0013516, 0.0013516
|
|
||||||
264, 0.02391, 0.024676, 0.0036971, 0.97962, 0.97023, 0.98219, 0.72072, 0.024265, 0.021404, 0.0017216, 0.0013336, 0.0013336, 0.0013336
|
|
||||||
265, 0.02313, 0.024861, 0.0031131, 0.97831, 0.97705, 0.9824, 0.71233, 0.023289, 0.021431, 0.001778, 0.001316, 0.001316, 0.001316
|
|
||||||
266, 0.022911, 0.023178, 0.0040326, 0.9855, 0.95678, 0.97393, 0.70797, 0.023489, 0.021917, 0.001843, 0.0012989, 0.0012989, 0.0012989
|
|
||||||
267, 0.022923, 0.025628, 0.0032744, 0.98466, 0.95676, 0.97389, 0.70614, 0.023732, 0.021756, 0.0018387, 0.0012822, 0.0012822, 0.0012822
|
|
||||||
268, 0.021734, 0.024794, 0.0037717, 0.97172, 0.9703, 0.9748, 0.69889, 0.023854, 0.021882, 0.0018406, 0.001266, 0.001266, 0.001266
|
|
||||||
269, 0.023233, 0.023997, 0.0026434, 0.98878, 0.95002, 0.97413, 0.69813, 0.024157, 0.022212, 0.0018839, 0.0012503, 0.0012503, 0.0012503
|
|
||||||
270, 0.022645, 0.024259, 0.0028535, 0.9733, 0.9703, 0.97535, 0.70777, 0.024298, 0.021893, 0.001847, 0.001235, 0.001235, 0.001235
|
|
||||||
271, 0.022842, 0.025684, 0.003931, 0.97335, 0.9703, 0.97546, 0.6987, 0.023966, 0.022058, 0.0018554, 0.0012202, 0.0012202, 0.0012202
|
|
||||||
272, 0.022658, 0.02243, 0.0029644, 0.98127, 0.97703, 0.97619, 0.70566, 0.024319, 0.022133, 0.0018315, 0.0012059, 0.0012059, 0.0012059
|
|
||||||
273, 0.021985, 0.023866, 0.003224, 0.97334, 0.97028, 0.97532, 0.71404, 0.02463, 0.021925, 0.0017855, 0.0011921, 0.0011921, 0.0011921
|
|
||||||
274, 0.021942, 0.025971, 0.0030934, 0.9921, 0.94045, 0.96804, 0.70548, 0.023867, 0.02181, 0.0017593, 0.0011787, 0.0011787, 0.0011787
|
|
||||||
275, 0.022654, 0.025224, 0.002868, 0.97576, 0.96344, 0.98036, 0.71113, 0.023825, 0.021833, 0.001792, 0.0011658, 0.0011658, 0.0011658
|
|
||||||
276, 0.022061, 0.023995, 0.0044932, 0.96396, 0.97519, 0.98094, 0.70244, 0.025151, 0.022106, 0.0018909, 0.0011533, 0.0011533, 0.0011533
|
|
||||||
277, 0.022082, 0.024009, 0.0043146, 0.9688, 0.96354, 0.96678, 0.69519, 0.025253, 0.022238, 0.0019813, 0.0011414, 0.0011414, 0.0011414
|
|
||||||
278, 0.022718, 0.025438, 0.0033991, 0.98149, 0.97029, 0.96863, 0.69842, 0.024404, 0.021862, 0.0021195, 0.0011299, 0.0011299, 0.0011299
|
|
||||||
279, 0.021459, 0.024987, 0.0033223, 0.98556, 0.96354, 0.97556, 0.70391, 0.024428, 0.021777, 0.002116, 0.0011189, 0.0011189, 0.0011189
|
|
||||||
280, 0.022531, 0.025328, 0.0029854, 0.97082, 0.97026, 0.98069, 0.70413, 0.024501, 0.021852, 0.0020207, 0.0011084, 0.0011084, 0.0011084
|
|
||||||
281, 0.021432, 0.02498, 0.0037385, 0.97039, 0.9703, 0.98025, 0.70643, 0.024077, 0.021808, 0.0018792, 0.0010983, 0.0010983, 0.0010983
|
|
||||||
282, 0.022082, 0.024033, 0.0035464, 0.97989, 0.97705, 0.98222, 0.70106, 0.023699, 0.021782, 0.0018304, 0.0010888, 0.0010888, 0.0010888
|
|
||||||
283, 0.022438, 0.026502, 0.0037712, 0.97219, 0.97702, 0.9805, 0.70248, 0.023944, 0.022022, 0.0018007, 0.0010797, 0.0010797, 0.0010797
|
|
||||||
284, 0.021952, 0.026204, 0.0030446, 0.9716, 0.977, 0.9802, 0.71073, 0.024671, 0.022283, 0.0017623, 0.0010711, 0.0010711, 0.0010711
|
|
||||||
285, 0.02244, 0.024696, 0.0031012, 0.97361, 0.9703, 0.98002, 0.71442, 0.024199, 0.022152, 0.0017836, 0.001063, 0.001063, 0.001063
|
|
||||||
286, 0.021664, 0.023039, 0.0027769, 0.97304, 0.96354, 0.97902, 0.70917, 0.023735, 0.022079, 0.0017841, 0.0010554, 0.0010554, 0.0010554
|
|
||||||
287, 0.022677, 0.025335, 0.0041636, 0.97759, 0.97705, 0.98093, 0.71153, 0.022869, 0.022005, 0.0017778, 0.0010483, 0.0010483, 0.0010483
|
|
||||||
288, 0.022281, 0.025492, 0.0036219, 0.98065, 0.97025, 0.98087, 0.70983, 0.022568, 0.022306, 0.0018028, 0.0010416, 0.0010416, 0.0010416
|
|
||||||
289, 0.023508, 0.024725, 0.0040105, 0.97198, 0.97023, 0.98068, 0.70539, 0.023018, 0.022493, 0.001852, 0.0010355, 0.0010355, 0.0010355
|
|
||||||
290, 0.023213, 0.024867, 0.0040221, 0.97374, 0.9703, 0.98036, 0.70964, 0.023247, 0.022265, 0.0018443, 0.0010298, 0.0010298, 0.0010298
|
|
||||||
291, 0.021429, 0.023571, 0.0036408, 0.97524, 0.96354, 0.97319, 0.7067, 0.023258, 0.022189, 0.0018254, 0.0010247, 0.0010247, 0.0010247
|
|
||||||
292, 0.021587, 0.024857, 0.0031796, 0.97449, 0.9703, 0.98051, 0.71474, 0.02327, 0.022178, 0.0018069, 0.00102, 0.00102, 0.00102
|
|
||||||
293, 0.022102, 0.02446, 0.0038188, 0.9726, 0.9703, 0.98018, 0.71203, 0.023105, 0.022171, 0.0017905, 0.0010158, 0.0010158, 0.0010158
|
|
||||||
294, 0.021959, 0.024979, 0.0029226, 0.98156, 0.9703, 0.97487, 0.70595, 0.022793, 0.022188, 0.0018304, 0.0010121, 0.0010121, 0.0010121
|
|
||||||
295, 0.021182, 0.025238, 0.0033527, 0.96627, 0.9703, 0.97301, 0.71552, 0.023089, 0.021885, 0.0018715, 0.0010089, 0.0010089, 0.0010089
|
|
||||||
296, 0.022339, 0.024582, 0.0034718, 0.96882, 0.97705, 0.98079, 0.719, 0.023042, 0.021523, 0.0018468, 0.0010062, 0.0010062, 0.0010062
|
|
||||||
297, 0.022934, 0.025444, 0.0036708, 0.97071, 0.97619, 0.9806, 0.72045, 0.023387, 0.021511, 0.0017952, 0.0010039, 0.0010039, 0.0010039
|
|
||||||
298, 0.022714, 0.024515, 0.004176, 0.97351, 0.97029, 0.98062, 0.71732, 0.023228, 0.021938, 0.0018586, 0.0010022, 0.0010022, 0.0010022
|
|
||||||
299, 0.022972, 0.026098, 0.0036222, 0.98, 0.97705, 0.98277, 0.70426, 0.023559, 0.022199, 0.0019408, 0.001001, 0.001001, 0.001001
|
|
||||||
|
|
Before Width: | Height: | Size: 213 KiB |
|
Before Width: | Height: | Size: 737 KiB |
|
Before Width: | Height: | Size: 844 KiB |
|
Before Width: | Height: | Size: 804 KiB |
|
Before Width: | Height: | Size: 546 KiB |
|
Before Width: | Height: | Size: 546 KiB |
|
Before Width: | Height: | Size: 586 KiB |
|
Before Width: | Height: | Size: 585 KiB |
25
ros2_ws/src/yolov3_ros/launch/pipe_detection.launch.py
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
|
||||||
|
# Launch arguments
|
||||||
|
DeclareLaunchArgument('best_weights', default_value='src/pipe_weights.pt', description='Path to best weights file (.pt)'),
|
||||||
|
|
||||||
|
# Nodes to launch
|
||||||
|
Node(
|
||||||
|
package='yolov3_ros', executable='yolov3_ros_node', output='screen',
|
||||||
|
parameters=[{
|
||||||
|
'best_weights':LaunchConfiguration('best_weights'),
|
||||||
|
}],
|
||||||
|
# remappings=[
|
||||||
|
# ('rgb_img', LaunchConfiguration('rgb_topic')),
|
||||||
|
# ('depth_img', LaunchConfiguration('depth_topic')),
|
||||||
|
# ('camera_info', LaunchConfiguration('camera_info_topic'))]
|
||||||
|
),
|
||||||
|
])
|
||||||
BIN
ros2_ws/src/yolov3_ros/models/__pycache__/common.cpython-310.pyc
Normal file
BIN
ros2_ws/src/yolov3_ros/models/__pycache__/yolo.cpython-310.pyc
Normal file
51
ros2_ws/src/yolov3_ros/models/yolov3.yaml
Normal file
@ -0,0 +1,51 @@
|
|||||||
|
# YOLOv3 🚀 by Ultralytics, GPL-3.0 license
|
||||||
|
|
||||||
|
# Parameters
|
||||||
|
nc: 4 # number of classes
|
||||||
|
depth_multiple: 1.0 # model depth multiple
|
||||||
|
width_multiple: 1.0 # layer channel multiple
|
||||||
|
anchors:
|
||||||
|
- [10,13, 16,30, 33,23] # P3/8
|
||||||
|
- [30,61, 62,45, 59,119] # P4/16
|
||||||
|
- [116,90, 156,198, 373,326] # P5/32
|
||||||
|
|
||||||
|
# darknet53 backbone
|
||||||
|
backbone:
|
||||||
|
# [from, number, module, args]
|
||||||
|
[[-1, 1, Conv, [32, 3, 1]], # 0
|
||||||
|
[-1, 1, Conv, [64, 3, 2]], # 1-P1/2
|
||||||
|
[-1, 1, Bottleneck, [64]],
|
||||||
|
[-1, 1, Conv, [128, 3, 2]], # 3-P2/4
|
||||||
|
[-1, 2, Bottleneck, [128]],
|
||||||
|
[-1, 1, Conv, [256, 3, 2]], # 5-P3/8
|
||||||
|
[-1, 8, Bottleneck, [256]],
|
||||||
|
[-1, 1, Conv, [512, 3, 2]], # 7-P4/16
|
||||||
|
[-1, 8, Bottleneck, [512]],
|
||||||
|
[-1, 1, Conv, [1024, 3, 2]], # 9-P5/32
|
||||||
|
[-1, 4, Bottleneck, [1024]], # 10
|
||||||
|
]
|
||||||
|
|
||||||
|
# YOLOv3 head
|
||||||
|
head:
|
||||||
|
[[-1, 1, Bottleneck, [1024, False]],
|
||||||
|
[-1, 1, Conv, [512, 1, 1]],
|
||||||
|
[-1, 1, Conv, [1024, 3, 1]],
|
||||||
|
[-1, 1, Conv, [512, 1, 1]],
|
||||||
|
[-1, 1, Conv, [1024, 3, 1]], # 15 (P5/32-large)
|
||||||
|
|
||||||
|
[-2, 1, Conv, [256, 1, 1]],
|
||||||
|
[-1, 1, nn.Upsample, [None, 2, 'nearest']],
|
||||||
|
[[-1, 8], 1, Concat, [1]], # cat backbone P4
|
||||||
|
[-1, 1, Bottleneck, [512, False]],
|
||||||
|
[-1, 1, Bottleneck, [512, False]],
|
||||||
|
[-1, 1, Conv, [256, 1, 1]],
|
||||||
|
[-1, 1, Conv, [512, 3, 1]], # 22 (P4/16-medium)
|
||||||
|
|
||||||
|
[-2, 1, Conv, [128, 1, 1]],
|
||||||
|
[-1, 1, nn.Upsample, [None, 2, 'nearest']],
|
||||||
|
[[-1, 6], 1, Concat, [1]], # cat backbone P3
|
||||||
|
[-1, 1, Bottleneck, [256, False]],
|
||||||
|
[-1, 2, Bottleneck, [256, False]], # 27 (P3/8-small)
|
||||||
|
|
||||||
|
[[27, 22, 15], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5)
|
||||||
|
]
|
||||||
18
ros2_ws/src/yolov3_ros/package.xml
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>yolov3_ros</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>TODO: Package description</description>
|
||||||
|
<maintainer email="eic.apoorva@gmail.com">parallels</maintainer>
|
||||||
|
<license>TODO: License declaration</license>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>ament_pep257</test_depend>
|
||||||
|
<test_depend>python3-pytest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
4
ros2_ws/src/yolov3_ros/setup.cfg
Normal file
@ -0,0 +1,4 @@
|
|||||||
|
[develop]
|
||||||
|
script_dir=$base/lib/yolov3_ros
|
||||||
|
[install]
|
||||||
|
install_scripts=$base/lib/yolov3_ros
|
||||||
43
ros2_ws/src/yolov3_ros/setup.py
Normal file
@ -0,0 +1,43 @@
|
|||||||
|
from setuptools import setup
|
||||||
|
import os
|
||||||
|
from glob import glob
|
||||||
|
|
||||||
|
package_name = 'yolov3_ros'
|
||||||
|
|
||||||
|
setup(
|
||||||
|
name=package_name,
|
||||||
|
version='0.0.0',
|
||||||
|
packages=[
|
||||||
|
package_name
|
||||||
|
],
|
||||||
|
data_files=[
|
||||||
|
('share/ament_index/resource_index/packages',
|
||||||
|
['resource/' + package_name]),
|
||||||
|
('share/' + package_name, ['package.xml']),
|
||||||
|
(os.path.join('lib', package_name, 'models'), glob('models/*.py')),
|
||||||
|
(os.path.join('lib', package_name, 'models'), glob('models/segment/*')),
|
||||||
|
(os.path.join('lib', package_name, 'models'), glob('models/hub/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/*.py')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/aws/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/docker/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/flask_rest_api/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/google_app_engine/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/loggers/comet/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/loggers/wandb/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/loggers/clearml/*')),
|
||||||
|
(os.path.join('lib', package_name, 'utils'), glob('utils/segment/*')),
|
||||||
|
(os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py')),
|
||||||
|
],
|
||||||
|
install_requires=['setuptools'],
|
||||||
|
zip_safe=True,
|
||||||
|
maintainer='parallels',
|
||||||
|
maintainer_email='eic.apoorva@gmail.com',
|
||||||
|
description='TODO: Package description',
|
||||||
|
license='TODO: License declaration',
|
||||||
|
tests_require=['pytest'],
|
||||||
|
entry_points={
|
||||||
|
'console_scripts': [
|
||||||
|
'yolov3_ros_node = yolov3_ros.yolov3_ros_node:main'
|
||||||
|
],
|
||||||
|
},
|
||||||
|
)
|
||||||
25
ros2_ws/src/yolov3_ros/test/test_copyright.py
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_copyright.main import main
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
|
||||||
|
# Remove the `skip` decorator once the source file(s) have a copyright header
|
||||||
|
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
|
||||||
|
@pytest.mark.copyright
|
||||||
|
@pytest.mark.linter
|
||||||
|
def test_copyright():
|
||||||
|
rc = main(argv=['.', 'test'])
|
||||||
|
assert rc == 0, 'Found errors'
|
||||||
25
ros2_ws/src/yolov3_ros/test/test_flake8.py
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
# Copyright 2017 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_flake8.main import main_with_errors
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.mark.flake8
|
||||||
|
@pytest.mark.linter
|
||||||
|
def test_flake8():
|
||||||
|
rc, errors = main_with_errors(argv=[])
|
||||||
|
assert rc == 0, \
|
||||||
|
'Found %d code style errors / warnings:\n' % len(errors) + \
|
||||||
|
'\n'.join(errors)
|
||||||
23
ros2_ws/src/yolov3_ros/test/test_pep257.py
Normal file
@ -0,0 +1,23 @@
|
|||||||
|
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_pep257.main import main
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.mark.linter
|
||||||
|
@pytest.mark.pep257
|
||||||
|
def test_pep257():
|
||||||
|
rc = main(argv=['.', 'test'])
|
||||||
|
assert rc == 0, 'Found code style errors / warnings'
|
||||||