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
00027
00028
00029
00030 #include "ui_camera_focus.h"
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
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
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
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
00139
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
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155
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
00164
00165
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
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
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
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
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
00287
00288
00289
00290
00291
00292 }