00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00035 #include <stdio.h>
00036 #include <ros/ros.h>
00037 #include <laser_geometry/laser_geometry.h>
00038 #include <sensor_msgs/LaserScan.h>
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <tf/transform_listener.h>
00041 #include <pcl_ros/transforms.h>
00042 #include <pcl/ros/conversions.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00046 #include <pcl/filters/extract_indices.h>
00047 #include <pcl/filters/project_inliers.h>
00048 #include <sensor_msgs/JointState.h>
00049
00050
00051 #define PFLN printf("file %s line %d\n",__FILE__,__LINE__);
00052
00053 #define _USE_DEBUG_ 0
00054
00055 ros::NodeHandle* p_n;
00056 tf::TransformListener *p_listener;
00057 double current_pan=0, current_tilt=0;
00058 ros::Publisher pub;
00059
00060 void target_pose_cb(const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
00061 {
00062 pcl::PointCloud<pcl::PointXYZ> pc_in;
00063 pcl::PointCloud<pcl::PointXYZ> pc_transformed;
00064 tf::StampedTransform transform;
00065
00066
00067 try
00068 {
00069 p_listener->lookupTransform(pcmsg_in->header.frame_id, "/atc/ptu/tilt_block", ros::Time(0), transform);
00070 }
00071 catch (tf::TransformException ex)
00072 {
00073 ROS_ERROR("%s",ex.what());
00074 ROS_ERROR("Cannot find transform, returning");
00075 }
00076
00077 pcl::fromROSMsg(*pcmsg_in,pc_in);
00078
00079 pcl_ros::transformPointCloud(pc_in,pc_transformed,transform.inverse());
00080 pc_transformed.header.frame_id = "/atc/ptu/tilt_block";
00081
00082 double target_x = pc_transformed.points[0].x;
00083 double target_y = pc_transformed.points[0].y;
00084 double target_z = pc_transformed.points[0].z;
00085
00086 double delta_pan = atan2(target_y,target_x);
00087 double delta_tilt = atan2(target_z, sqrt(target_x*target_x+target_y*target_y));
00088
00089 double new_pan = current_pan + delta_pan;
00090 double new_tilt = current_tilt + delta_tilt;
00091
00092 sensor_msgs::JointState joint_state;
00093 joint_state.header.stamp = ros::Time::now();
00094 joint_state.name.resize(2);
00095 joint_state.position.resize(2);
00096
00097 joint_state.name[0] =ros::names::remap("pan");
00098 joint_state.position[0] = new_pan;
00099
00100 joint_state.name[1] =ros::names::remap("tilt");
00101 joint_state.position[1] = new_tilt;
00102
00103 pub.publish(joint_state);
00104
00105 }
00106
00107
00108
00109
00110 int main(int argc, char **argv)
00111 {
00112
00113 ros::init(argc, argv, "foveation_control");
00114 ros::NodeHandle n("~");
00115 tf::TransformListener listener(n,ros::Duration(10));
00116 p_listener=&listener;
00117 p_n=&n;
00118
00119 ros::Subscriber sub = n.subscribe("/target", 1, target_pose_cb);
00120
00121
00122 pub = n.advertise<sensor_msgs::JointState>("/ptu_cmd", 1);
00123
00124 ros::Rate loop_rate(10);
00125 ros::spin();
00126
00127 }