pantilt.cpp
Go to the documentation of this file.
00001 /*
00002  * pantilt
00003  * Copyright (c) 2008, Willow Garage, Inc.
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of the <ORGANIZATION> nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  */
00030 
00031 // Author: Dallas Goecker
00032 
00033 // Controls pan and tilt feature of Logitech Orbit camera.  Will probably work 
00034 // for other USB pand/tilt cameras.
00035 //
00036 // Subscribes to /joy messages an input control of camera.  This should probably
00037 // subscribe a to pan/tilt like message then have another node/service translate 
00038 // joy messages to pan/tilt messages.  But this is a quick first pass.
00039 //
00040 // joy.axes[] values are expected to range between -1 and 1.
00041 
00042 #include <ros/ros.h>
00043 #include <sensor_msgs/Joy.h>
00044 #include <corobot_msgs/PanTilt.h>
00045 
00046 #include <stdio.h>
00047 #include <stdlib.h>
00048 #include <unistd.h>
00049 #include <string.h>
00050 #include <fcntl.h>
00051 #include <linux/videodev2.h>
00052 #include <sys/ioctl.h>
00053 #include <errno.h>
00054 #include <diagnostic_updater/diagnostic_updater.h>
00055 #include <diagnostic_updater/publisher.h>
00056 
00057 extern "C" {
00058   #include "dynctrl.h"
00059 }
00060 
00061 #define BITS_PER_DEGREE (64)
00062 #define MAX_PAN_DEG  (70)
00063 #define MIN_PAN_DEG  (-70)
00064 #define MAX_TILT_DEG (30)
00065 #define MIN_TILT_DEG (-30)
00066 #define MIN_STEP_DEG (2)
00067 
00068 int pantilt_reset(int fd);
00069 int pantilt_move(int fd, int pan, int tilt);
00070 void pantilt_check_speed(int fd);
00071 
00072 static int cam_fd;
00073 int pantiltError = 0; // use for diagnostics purpose
00074 
00075 void pantiltCallback(const corobot_msgs::PanTiltConstPtr& msg)
00076 {
00077   if (msg->reset) {
00078     pantilt_reset(cam_fd);
00079     ROS_INFO("PanTilt reset");
00080   } else {
00081     ROS_INFO("PanTilt moving pan=%d, tilt=%d", msg->pan, msg->tilt);
00082     pantilt_move(cam_fd,msg->pan, msg->tilt);
00083   }
00084 }
00085 
00089 void joyCallback(const sensor_msgs::JoyConstPtr& msg)
00090 {
00091   // msg.axes->length();
00092   const float joy_to_pan_gain = 10;
00093   const float joy_to_tilt_gain = 5;
00094   const int axis_pan = 0;
00095   const int axis_tilt = 1;
00096   const int button_reset = 4;
00097   const int button_right35 = 7;
00098   const int button_left35 = 5;
00099   int pan_inc_deg, tilt_inc_deg;
00100   int reset_button_previous = 0;
00101 
00102   // The length of the buttons & axes array is only as long as the largest button number pushed.
00103   // Check length.
00104   if (msg->buttons.size() > (unsigned int)button_reset && msg->buttons[button_reset] && !reset_button_previous) {
00105     reset_button_previous = 1;
00106     pantilt_reset(cam_fd);
00107     ROS_INFO("PanTilt reset");
00108   }
00109   else if (msg->buttons.size() > (unsigned int)button_right35 && msg->buttons[button_right35]) {
00110     pantilt_move(cam_fd,35,0);
00111     ROS_INFO("PanTilt moving pan=+35");
00112   }
00113   else if (msg->buttons.size() > (unsigned int)button_left35 && msg->buttons[button_left35]) {
00114     pantilt_move(cam_fd,-35,0);
00115     ROS_INFO("PanTilt moving pan=-35");
00116   }
00117   else {
00118     reset_button_previous = 0;
00119     if (msg->axes.size() > (unsigned int)axis_pan) {
00120       pan_inc_deg = int(msg->axes[axis_pan] * joy_to_pan_gain);
00121     } else {
00122       pan_inc_deg = 0;
00123     }
00124     if (msg->axes.size() > (unsigned int)axis_tilt) {
00125       tilt_inc_deg = int(msg->axes[axis_tilt] * joy_to_tilt_gain * -1);
00126     } else {
00127       tilt_inc_deg = 0;
00128     }
00129     if (pan_inc_deg >= 1 || tilt_inc_deg >= 1 || pan_inc_deg <= -1 || tilt_inc_deg <= -1) {
00130       pantilt_move(cam_fd,pan_inc_deg, tilt_inc_deg);
00131       ROS_INFO("PanTilt moving pan=%d, tilt=%d", pan_inc_deg, tilt_inc_deg);
00132     }
00133   }
00134 }
00135 
00136 void pantilt_diagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
00140 {
00141         if (!pantiltError)  
00142                 stat.summaryf(diagnostic_msgs::DiagnosticStatus::OK, "initialized");
00143         else if (pantiltError == 1)
00144         {
00145                 stat.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "Cannot be initialized");
00146                 stat.addf("Recommendation", "Please make sure the port path is the correct one. Make sure the permissions are correct and that the camera has pan tilt option");
00147         }
00148         else if (pantiltError == 2)
00149         {
00150                 stat.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "Cannot move camera");
00151                 stat.addf("Recommendation", "Please make sure the port path is the correct one. Make sure the permissions are correct and that the camera has pan tilt option");
00152         }
00153 }
00154 
00155 int main(int argc, char** argv)
00156 {
00157   std::string dev;
00158   std::string path;
00159   ros::init(argc, argv, "pantilt");
00160   ros::NodeHandle n;
00161   ros::NodeHandle nh("~");
00162   
00163  nh.param<std::string>("device",dev, "/dev/video0");
00164  nh.param<std::string>("script_path",path, "init_camera.sh");
00165 
00166   //create an updater that will send information on the diagnostics topics
00167   diagnostic_updater::Updater updater;
00168   updater.setHardwareIDf("PanTIlt");
00169   updater.add("PanTilt", pantilt_diagnostic); //function that will be executed with updater.update()
00170 
00171 //Execute a script to initialize the camera 
00172 
00173   //system(path.c_str());
00174   if ((cam_fd = open(dev.c_str(), O_RDWR)) == -1) {
00175     ROS_ERROR("PanTilt could not open %s interface\n",dev.c_str());
00176     pantiltError = 1;
00177   }
00178   else
00179     pantiltError = 0;
00180 
00181   ROS_INFO("PanTilt Opened: %s\n",dev.c_str());
00182   initDynCtrls(cam_fd);
00183   ROS_INFO("PanTilt Initilized: %s\n",dev.c_str());
00184 
00185   ROS_INFO("PanTilt note int(1.4)=%d, int(-1.4)=%d", int(1.4), int(-1.4));
00186   
00187   ros::Subscriber joy_sub = n.subscribe("/joy", 1, joyCallback);
00188   ros::Subscriber pantilt_sub = n.subscribe("/pantilt", 1, pantiltCallback);
00189 
00190   while (ros::ok())
00191   {
00192         ros::spinOnce();
00193         updater.update();
00194   }
00195 
00196   close(cam_fd);
00197   return 0;
00198 }
00199 
00200 
00201 void pantilt_check_speed(int fd) {
00202   int i, repeat, step, pan;
00203 
00204   sleep(1);
00205   printf("reseting...");
00206   pantilt_reset(fd);
00207   printf("done.\n");
00208   sleep(1);
00209 
00210   for (step=2;step<=20;step=step+5) {
00211     printf("Step=%d: ",step);
00212     for (repeat=0;repeat<3;repeat++) {
00213       printf("%d,",repeat+1);
00214       pan = 0;
00215       for (i=step;i<60;i=i+step) {
00216         pantilt_move(fd,step,0);
00217         pan += step;
00218       }
00219       pantilt_move(fd,-pan,0);
00220       sleep(1);
00221     }
00222     printf("done.\n");
00223     pantilt_reset(fd);
00224     printf("reset.\n");
00225     sleep(1);
00226   }
00227 }
00228 
00229 int pantilt_reset(int fd) {
00230   int result;
00231   result = uvcPanTilt(fd, 0, 0, 3);
00232 
00233   if (result == -1)
00234         pantiltError = 2;
00235   else
00236         pantiltError = 0;
00237 
00238   sleep(2);
00239   return result;
00240 }
00241 
00242 int pantilt_move(int fd, int pan, int tilt){
00243   int result;
00244   result = uvcPanTilt(fd, pan*BITS_PER_DEGREE, tilt*BITS_PER_DEGREE, 0);
00245   //usleep((70+10*abs(pan))*1000);  // moving delay??
00246 
00247   if (result == -1)
00248         pantiltError = 2;
00249   else
00250         pantiltError = 0;
00251   return result;
00252 }
00253 
00254 
00255 
00256 
00257 
00258 
00259 
00260 


corobot_pantilt
Author(s): Morgan Cormier/mcormier@coroware.com
autogenerated on Tue Jan 7 2014 11:39:02