Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added topic to track pixel position of the center of marker #21

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 15 additions & 6 deletions launch/whycon.launch
Original file line number Diff line number Diff line change
@@ -1,16 +1,25 @@
<launch>
<arg name="name" default="whycon"/>
<arg name="targets" default="1"/>

<group ns="camera">
<node pkg="image_proc" type="image_proc" name="image_proc"/>
</group>
<arg name="outer_diameter" default=".55"/>
<arg name="inner_diameter" default=".20"/>
<arg name="input_queue_size" default="100"/>

<node name="whycon" type="whycon" pkg="whycon" output="screen">
<param name="targets" value="$(arg targets)"/>
<param name="outer_diameter" value="$(arg outer_diameter)"/>
<param name="inner_diameter" value="$(arg inner_diameter)"/>
<param name="input_queue_size" value="$(arg input_queue_size)"/>
<param name="name" value="$(arg name)"/>

<remap to=" " from=" " />
<remap to=" " from=" " />

</node>

<node name="transformer" type="transformer" pkg="whycon" output="screen"/>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/whycon/image_out"/>
<param name="autosize" value="true" />
</node>

</launch>

109 changes: 62 additions & 47 deletions src/ros/whycon_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,29 +10,29 @@

whycon::WhyConROS::WhyConROS(ros::NodeHandle& n) : is_tracking(false), should_reset(true), it(n)
{
transformation_loaded = false;
similarity.setIdentity();
transformation_loaded = false;
similarity.setIdentity();

if (!n.getParam("targets", targets)) throw std::runtime_error("Private parameter \"targets\" is missing");

n.param("name", frame_id, std::string("whycon"));
n.param("world_frame", world_frame_id, std::string("world"));
n.param("world_frame", world_frame_id, std::string("world"));
n.param("max_attempts", max_attempts, 1);
n.param("max_refine", max_refine, 1);

n.getParam("outer_diameter", parameters.outer_diameter);
n.getParam("inner_diameter", parameters.inner_diameter);
n.getParam("center_distance_tolerance_abs", parameters.center_distance_tolerance_abs);
n.getParam("center_distance_tolerance_ratio", parameters.center_distance_tolerance_ratio);
n.getParam("roundness_tolerance", parameters.roundness_tolerance);
n.getParam("circularity_tolerance", parameters.circularity_tolerance);
n.getParam("max_size", parameters.max_size);
n.getParam("min_size", parameters.min_size);
n.getParam("ratio_tolerance", parameters.ratio_tolerance);
n.getParam("max_eccentricity", parameters.max_eccentricity);
n.getParam("outer_diameter", parameters.outer_diameter);
n.getParam("inner_diameter", parameters.inner_diameter);
n.getParam("center_distance_tolerance_abs", parameters.center_distance_tolerance_abs);
n.getParam("center_distance_tolerance_ratio", parameters.center_distance_tolerance_ratio);
n.getParam("roundness_tolerance", parameters.roundness_tolerance);
n.getParam("circularity_tolerance", parameters.circularity_tolerance);
n.getParam("max_size", parameters.max_size);
n.getParam("min_size", parameters.min_size);
n.getParam("ratio_tolerance", parameters.ratio_tolerance);
n.getParam("max_eccentricity", parameters.max_eccentricity);

load_transforms();
transform_broadcaster = boost::make_shared<tf::TransformBroadcaster>();
load_transforms();
transform_broadcaster = boost::make_shared<tf::TransformBroadcaster>();

/* initialize ros */
int input_queue_size = 1;
Expand All @@ -42,7 +42,9 @@ whycon::WhyConROS::WhyConROS(ros::NodeHandle& n) : is_tracking(false), should_re
image_pub = n.advertise<sensor_msgs::Image>("image_out", 1);
poses_pub = n.advertise<geometry_msgs::PoseArray>("poses", 1);
context_pub = n.advertise<sensor_msgs::Image>("context", 1);
projection_pub = n.advertise<whycon::Projection>("projection", 1);
projection_pub = n.advertise<whycon::Projection>("projection", 1);

circlecenter_pub = n.advertise<geometry_msgs::PoseArray>("circle_center", 1);

reset_service = n.advertiseService("reset", &WhyConROS::reset, this);
}
Expand Down Expand Up @@ -95,22 +97,35 @@ void whycon::WhyConROS::publish_results(const std_msgs::Header& header, const cv
output_image = cv_ptr->image.clone();

geometry_msgs::PoseArray pose_array;

geometry_msgs::PoseArray circle_pose;
// go through detected targets

for (int i = 0; i < system->targets; i++) {
const whycon::CircleDetector::Circle& circle = system->get_circle(i);

geometry_msgs::Pose c;
c.position.x = circle.x;
c.position.y = circle.y;
c.position.z = 0;
circle_pose.poses.push_back(c);
//circle_pose.position.x = circle.x;
//circle_pose.position.y = circle.y;
//circle_pose.position.z = 0;
circlecenter_pub.publish(circle_pose);

whycon::LocalizationSystem::Pose pose = system->get_pose(circle);
cv::Vec3f coord = pose.pos;


// draw each target
if (publish_images) {
std::ostringstream ostr;
ostr << std::fixed << std::setprecision(2);
ostr << coord << " " << i;
ostr << coord << " " << i;
circle.draw(output_image, ostr.str(), cv::Vec3b(0,255,255));
/*whycon::CircleDetector::Circle new_circle = circle.improveEllipse(cv_ptr->image);
new_circle.draw(output_image, ostr.str(), cv::Vec3b(0,255,0));*/
cv::circle(output_image, camera_model.project3dToPixel(cv::Point3d(coord)), 1, cv::Scalar(255,0,255), 1, CV_AA);
// whycon::CircleDetector::Circle new_circle = circle.improveEllipse(cv_ptr->image);
// new_circle.draw(output_image, ostr.str(), cv::Vec3b(0,255,0));
cv::circle(output_image, camera_model.project3dToPixel(cv::Point3d(coord)), 1, cv::Scalar(255,0,255), 1, CV_AA);
}

if (publish_poses) {
Expand All @@ -137,47 +152,47 @@ void whycon::WhyConROS::publish_results(const std_msgs::Header& header, const cv

if (transformation_loaded)
{
transform_broadcaster->sendTransform(tf::StampedTransform(similarity, header.stamp, world_frame_id, frame_id));
transform_broadcaster->sendTransform(tf::StampedTransform(similarity, header.stamp, world_frame_id, frame_id));

whycon::Projection projection_msg;
projection_msg.header = header;
for (size_t i = 0; i < projection.size(); i++) projection_msg.projection[i] = projection[i];
projection_pub.publish(projection_msg);
whycon::Projection projection_msg;
projection_msg.header = header;
for (size_t i = 0; i < projection.size(); i++) projection_msg.projection[i] = projection[i];
projection_pub.publish(projection_msg);
}
}

void whycon::WhyConROS::load_transforms(void)
{
std::string filename = frame_id + "_transforms.yml";
ROS_INFO_STREAM("Loading file " << filename);
std::string filename = frame_id + "_transforms.yml";
ROS_INFO_STREAM("Loading file " << filename);

std::ifstream file(filename);
if (!file) {
ROS_WARN_STREAM("Could not load \"" << filename << "\"");
return;
}
std::ifstream file(filename);
if (!file) {
ROS_WARN_STREAM("Could not load \"" << filename << "\"");
return;
}

YAML::Node node = YAML::Load(file);
YAML::Node node = YAML::Load(file);

projection.resize(9);
for (int i = 0; i < 9; i++)
projection[i] = node["projection"][i].as<double>();
projection.resize(9);
for (int i = 0; i < 9; i++)
projection[i] = node["projection"][i].as<double>();

std::vector<double> similarity_origin(3);
for (int i = 0; i < 3; i++) similarity_origin[i] = node["similarity"]["origin"][i].as<double>();
std::vector<double> similarity_origin(3);
for (int i = 0; i < 3; i++) similarity_origin[i] = node["similarity"]["origin"][i].as<double>();

std::vector<double> similarity_rotation(4);
for (int i = 0; i < 4; i++) similarity_rotation[i] = node["similarity"]["rotation"][i].as<double>();
std::vector<double> similarity_rotation(4);
for (int i = 0; i < 4; i++) similarity_rotation[i] = node["similarity"]["rotation"][i].as<double>();

tf::Vector3 origin(similarity_origin[0], similarity_origin[1], similarity_origin[2]);
tf::Quaternion Q(similarity_rotation[0], similarity_rotation[1], similarity_rotation[2], similarity_rotation[3]);
tf::Vector3 origin(similarity_origin[0], similarity_origin[1], similarity_origin[2]);
tf::Quaternion Q(similarity_rotation[0], similarity_rotation[1], similarity_rotation[2], similarity_rotation[3]);

similarity.setOrigin(origin);
similarity.setRotation(Q);
similarity.setOrigin(origin);
similarity.setRotation(Q);

transformation_loaded = true;
transformation_loaded = true;

ROS_INFO_STREAM("Loaded transformation from \"" << filename << "\"");
ROS_INFO_STREAM("Loaded transformation from \"" << filename << "\"");
}


4 changes: 2 additions & 2 deletions src/ros/whycon_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,15 +28,15 @@ namespace whycon {
std::string world_frame_id, frame_id;
int targets;
double xscale, yscale;

std::vector<double> projection;
tf::Transform similarity;

image_transport::ImageTransport it;
image_transport::CameraSubscriber cam_sub;
ros::ServiceServer reset_service;

ros::Publisher image_pub, poses_pub, context_pub, projection_pub;
ros::Publisher image_pub, poses_pub, context_pub, projection_pub, circlecenter_pub;
boost::shared_ptr<tf::TransformBroadcaster> transform_broadcaster;

image_geometry::PinholeCameraModel camera_model;
Expand Down