camera_focus_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "ui_camera_focus.h" // generated by uic from camera_focus.ui
00031 
00032 #include "pr2_interactive_manipulation/camera_focus_display.h"
00033 
00034 #include <rviz/window_manager_interface.h>
00035 #include <rviz/visualization_manager.h>
00036 #include <rviz/view_controller.h>
00037 #include <rviz/frame_manager.h>
00038 #include <rviz/panel_dock_widget.h>
00039 
00040 #include <OGRE/OgreMatrix3.h>
00041 
00042 #include <object_manipulator/tools/camera_configurations.h>
00043 
00044 namespace pr2_interactive_manipulation {
00045 
00046 CameraFocusDisplay::CameraFocusDisplay() : 
00047   Display(),
00048   frame_(NULL),
00049   frame_dock_(NULL)
00050 {
00051 }
00052   
00053 CameraFocusDisplay::~CameraFocusDisplay()
00054 {
00055   delete frame_dock_;
00056 }
00057 
00058 void CameraFocusDisplay::onEnable()
00059 {  
00060   if ( !frame_ )
00061   {
00062     rviz::WindowManagerInterface* window_manager = vis_manager_->getWindowManager();
00063     ROS_ASSERT(window_manager);
00064 
00065     frame_ = new CameraFocusFrame(vis_manager_, window_manager->getParentWindow());
00066     frame_dock_ = window_manager->addPane( "Camera Focus", frame_ );
00067   }
00068   frame_dock_->show();
00069 }
00070 
00071 void CameraFocusDisplay::onDisable()
00072 {
00073   if( frame_dock_ )
00074   {
00075     frame_dock_->hide();
00076   }
00077 }
00078 
00079 CameraFocusFrame::CameraFocusFrame(rviz::VisualizationManager* manager, QWidget* parent) :
00080   QWidget(parent),
00081   root_nh_(""),
00082   vis_manager_(manager),
00083   ui_( new Ui::CameraFocus )
00084 {
00085   ui_->setupUi( this );
00086   connect( ui_->left_button_, SIGNAL( clicked() ), this, SLOT( leftButtonClicked() ));
00087   connect( ui_->top_button_, SIGNAL( clicked() ), this, SLOT( topButtonClicked() ));
00088   connect( ui_->front_button_, SIGNAL( clicked() ), this, SLOT( frontButtonClicked() ));
00089   connect( ui_->right_button_, SIGNAL( clicked() ), this, SLOT( rightButtonClicked() ));
00090   connect( ui_->overhead_button_, SIGNAL( clicked() ), this, SLOT (overheadButtonClicked() ));
00091   connect( ui_->facing_button_, SIGNAL( clicked() ), this, SLOT (facingButtonClicked() ));
00092   //connect( ui_->accept_box_, SIGNAL( toggled() ), this, SLOT( acceptBoxToggled() ));
00093 
00094   sub_ = root_nh_.subscribe("/camera_focus", 10, &CameraFocusFrame::callback, this);    
00095 }
00096 
00097 CameraFocusFrame::~CameraFocusFrame()
00098 {
00099   delete ui_;
00100 }
00101 
00102 void CameraFocusFrame::callback(const pr2_object_manipulation_msgs::CameraFocusConstPtr &msg)
00103 {
00104   ROS_DEBUG("Camera focus message received");
00105   if (!ui_->accept_box_->isChecked()) {ROS_INFO("Camera focus: not accepting external commands"); return;}
00106 
00107   //transform point into target frame
00108   geometry_msgs::PointStamped point = msg->focal_point;
00109   point.header.stamp = ros::Time(0);
00110   try {
00111     vis_manager_->getFrameManager()->getTFClient()->transformPoint(vis_manager_->getTargetFrame(), 
00112                                                                    point, point );
00113   }
00114   catch(...)
00115   {
00116     ROS_ERROR("Camera focus: TF had a problem transforming between [%s] and [%s].",
00117               point.header.frame_id.c_str(), vis_manager_->getTargetFrame().c_str());
00118     return;
00119   }
00120   std::string params_string = vis_manager_->getCurrentViewController()->toString();
00121   ROS_DEBUG_STREAM("View params: " << params_string);
00122 
00123   //get the current params
00124   std::istringstream params_str(params_string); 
00125   std::vector<double> params;
00126   for (size_t i=0; i<6; i++)
00127   {
00128     double p;
00129     params_str >> p;
00130     if (params_str.fail())
00131     {
00132       ROS_ERROR("Camera focus: could not interpret params string");
00133       return;
00134     }
00135     params.push_back(p);
00136   }
00137 
00138   //set the desired point
00139   //arbitrary zoom at 1 meter
00140   params[2] = 1.5;
00141   params[3] = point.point.x;
00142   params[4] = point.point.y;
00143   params[5] = point.point.z;
00144 
00145   //set the camera params
00146   //setCamera(params);
00147   /*
00148   std::ostringstream os;
00149   for(int i=0; i<6; i++) os << params[i] << ' ';
00150   vis_manager_->getCurrentViewController()->fromString(os.str());
00151   vis_manager_->queueRender();
00152   ROS_DEBUG("Camera focus set");
00153   */
00154 
00155   //correct for yaw rotation
00156   float yaw_correction = 0;  
00157   Ogre::Vector3 pos;
00158   Ogre::Quaternion orient;
00159   if (rviz::FrameManager::instance()->getTransform("base_link", ros::Time(),  pos, orient) )
00160   {
00161     yaw_correction = orient.getRoll().valueRadians();
00162   }
00163   //we get the yaw from the current view here, so no need to correct for it
00164   //params[1] += yaw_correction; 
00165   //but we do need to rotate the focal point
00166   Ogre::Vector3 focal_point(params[3], params[4], params[5]);
00167   Ogre::Matrix3 rot;
00168   rot.FromAxisAngle(Ogre::Vector3(0,0,1), Ogre::Radian(yaw_correction));
00169   focal_point = rot * focal_point;
00170   for(int i=0; i<3; i++) params[3+i] = focal_point[i];
00171 
00172   //set the camera params
00173   std::ostringstream os;
00174   for(int i=0; i<6; i++) os << params[i] << ' ';
00175   vis_manager_->setTargetFrame("base_link");
00176   vis_manager_->setCurrentViewControllerType( "Orbit" );
00177   vis_manager_->getCurrentViewController()->fromString(os.str());
00178   vis_manager_->queueRender();
00179   printf("camera params: %s\n", os.str().c_str());
00180 }
00181 
00182 
00183 void CameraFocusFrame::setCamera(std::vector<double> params)
00184 {
00185   float yaw_correction = 0;
00186   Ogre::Vector3 pos;
00187   Ogre::Quaternion orient;
00188 
00189   //correct for yaw rotation
00190   if (rviz::FrameManager::instance()->getTransform("base_link", ros::Time(),  pos, orient) )
00191   {
00192     yaw_correction = orient.getRoll().valueRadians();
00193   }
00194   params[1] += yaw_correction;
00195   //also need to rotate the focal point
00196   Ogre::Vector3 focal_point(params[3], params[4], params[5]);
00197   Ogre::Matrix3 rot;
00198   rot.FromAxisAngle(Ogre::Vector3(0,0,1), Ogre::Radian(yaw_correction));
00199   focal_point = rot * focal_point;
00200   for(int i=0; i<3; i++) params[3+i] = focal_point[i];
00201 
00202   //set the camera params
00203   std::ostringstream os;
00204   for(int i=0; i<6; i++) os << params[i] << ' ';
00205   vis_manager_->setTargetFrame("base_link");
00206   vis_manager_->setCurrentViewControllerType( "Orbit" );
00207   vis_manager_->getCurrentViewController()->fromString(os.str());
00208   vis_manager_->queueRender();
00209   printf("camera params: %s\n", os.str().c_str());
00210 }
00211 
00212 
00213 void CameraFocusFrame::leftButtonClicked()
00214 {
00215   try
00216   {
00217     setCamera( object_manipulator::cameraConfigurations().get_camera_pose("left") );
00218   }
00219   catch(object_manipulator::BadParamException &ex)
00220   {
00221     ROS_ERROR("Pre-defined camera position not found");
00222   }
00223 }
00224 
00225 void CameraFocusFrame::topButtonClicked()
00226 {
00227   try
00228   {
00229     setCamera( object_manipulator::cameraConfigurations().get_camera_pose("top") );
00230   }
00231   catch(object_manipulator::BadParamException &ex)
00232   {
00233     ROS_ERROR("Pre-defined camera position not found");
00234   }
00235 }
00236 
00237 void CameraFocusFrame::frontButtonClicked()
00238 {
00239   try
00240   {
00241     setCamera( object_manipulator::cameraConfigurations().get_camera_pose("front") );
00242   }
00243   catch(object_manipulator::BadParamException &ex)
00244   {
00245     ROS_ERROR("Pre-defined camera position not found");
00246   }
00247 }
00248 
00249 void CameraFocusFrame::rightButtonClicked()
00250 {
00251   try
00252   {
00253     setCamera( object_manipulator::cameraConfigurations().get_camera_pose("right") );
00254   }
00255   catch(object_manipulator::BadParamException &ex)
00256   {
00257     ROS_ERROR("Pre-defined camera position not found");
00258   }
00259 }
00260 
00261 
00262 void CameraFocusFrame::overheadButtonClicked()
00263 {
00264   try
00265   {
00266     setCamera( object_manipulator::cameraConfigurations().get_camera_pose("overhead") );
00267   }
00268   catch(object_manipulator::BadParamException &ex)
00269   {
00270     ROS_ERROR("Pre-defined camera position not found");
00271   }
00272 }
00273 
00274 void CameraFocusFrame::facingButtonClicked()
00275 {
00276   try
00277   {
00278     setCamera( object_manipulator::cameraConfigurations().get_camera_pose("facing") );
00279   }
00280   catch(object_manipulator::BadParamException &ex)
00281   {
00282     ROS_ERROR("Pre-defined camera position not found");
00283   }
00284 }
00285 /*
00286 void CameraFocusFrame::acceptBoxToggled(bool checked)
00287 {
00288   if(checked) ROS_INFO("acceptBox checked");
00289   else ROS_INFO("acceptBox not checked!");
00290   }*/
00291 
00292 }


pr2_interactive_manipulation
Author(s): Matei Ciocarlie, Kaijen Hsiao, Adam Leeper
autogenerated on Fri Jan 3 2014 12:08:58