main.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
35 #include <stdio.h>
36 #include <ros/ros.h>
37 #include <laser_geometry/laser_geometry.h>
38 #include <sensor_msgs/LaserScan.h>
39 #include <sensor_msgs/PointCloud2.h>
40 #include <tf/transform_listener.h>
41 #include <pcl_ros/transforms.h>
42 #include <pcl/conversions.h>
43 #include <pcl/point_cloud.h>
44 #include <pcl/point_types.h>
45 #include <pcl/segmentation/extract_polygonal_prism_data.h>
46 #include <pcl/filters/extract_indices.h>
47 #include <pcl/filters/project_inliers.h>
48 #include <sensor_msgs/JointState.h>
49 #include <pcl_conversions/pcl_conversions.h>
50 
51 #define PFLN printf("file %s line %d\n",__FILE__,__LINE__);
52 
53 #define _USE_DEBUG_ 0
54 //Global variables
55 ros::NodeHandle* p_n;
56 tf::TransformListener *p_listener;
58 ros::Publisher pub;
59 
60 void target_pose_cb(const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
61 {
62  pcl::PointCloud<pcl::PointXYZ> pc_in;
63  pcl::PointCloud<pcl::PointXYZ> pc_transformed;
64  tf::StampedTransform transform;
65 
66  //p_listener->waitForTransform(pcmsg_in.header.frame_id, ros::names::remap("/tracking_frame"),ros::Time::now(), ros::Duration(0.2));
67  try
68  {
69  p_listener->lookupTransform(pcmsg_in->header.frame_id, "/atc/ptu/tilt_block", ros::Time(0), transform);
70  }
71  catch (tf::TransformException ex)
72  {
73  ROS_ERROR("%s",ex.what());
74  ROS_ERROR("Cannot find transform, returning");
75  }
76 
77 // pcl::fromROSMsg(*pcmsg_in,pc_in);
78 
79  pcl::PCLPointCloud2 pcl_pc;
80  pcl_conversions::toPCL(*pcmsg_in, pcl_pc);
81  pcl::fromPCLPointCloud2(pcl_pc, pc_in);
82 
83  pcl_ros::transformPointCloud(pc_in,pc_transformed,transform.inverse());
84  pc_transformed.header.frame_id = "/atc/ptu/tilt_block";
85 
86  double target_x = pc_transformed.points[0].x;
87  double target_y = pc_transformed.points[0].y;
88  double target_z = pc_transformed.points[0].z;
89 
90  double delta_pan = atan2(target_y,target_x);
91  double delta_tilt = atan2(target_z, sqrt(target_x*target_x+target_y*target_y));
92 
93  double new_pan = current_pan + delta_pan;
94  double new_tilt = current_tilt + delta_tilt;
95 
96  sensor_msgs::JointState joint_state;
97  joint_state.header.stamp = ros::Time::now();
98  joint_state.name.resize(2);
99  joint_state.position.resize(2);
100 
101  joint_state.name[0] =ros::names::remap("pan");
102  joint_state.position[0] = new_pan;
103 
104  joint_state.name[1] =ros::names::remap("tilt");
105  joint_state.position[1] = new_tilt;
106 
107  pub.publish(joint_state);
108 
109 }
110 
111 
112 
113 
114  int main(int argc, char **argv)
115  {
116 
117  ros::init(argc, argv, "foveation_control");
118  ros::NodeHandle n("~");
119  tf::TransformListener listener(n,ros::Duration(10));
120  p_listener=&listener;
121  p_n=&n;
122 
123  ros::Subscriber sub = n.subscribe("/target", 1, target_pose_cb);
124 
125  //declare the publisher
126  pub = n.advertise<sensor_msgs::JointState>("/ptu_cmd", 1);
127 
128  ros::Rate loop_rate(10);
129  ros::spin();
130 
131  }
double current_pan
Definition: main.cpp:57
int main(int argc, char **argv)
Definition: main.cpp:114
ros::NodeHandle * p_n
Definition: main.cpp:55
tf::TransformListener * p_listener
Definition: main.cpp:56
double current_tilt
Definition: main.cpp:57
ros::Publisher pub
Definition: main.cpp:58
void target_pose_cb(const sensor_msgs::PointCloud2ConstPtr &pcmsg_in)
Definition: main.cpp:60


foveation_control
Author(s): Miguel Oliveira
autogenerated on Mon Mar 2 2015 01:31:39