trajectory.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Mario Prats */
00036 
00037 #include <trajectory.h>
00038 #include <job_processing.h>
00039 
00040 #include <eigen_conversions/eigen_msg.h>
00041 
00042 #include <boost/math/constants/constants.hpp>
00043 
00044 #include <QWidget>
00045 
00046 namespace benchmark_tool
00047 {
00048 
00049 const std::string Trajectory::TRAJECTORY_SET_START_POSE_STRING = "Set start pose";
00050 const std::string Trajectory::TRAJECTORY_SET_END_POSE_STRING = "Set end pose";
00051 const std::string Trajectory::TRAJECTORY_EDIT_CONTROL_FRAME_STRING = "Edit control frame";
00052 const std::string Trajectory::TRAJECTORY_FIX_CONTROL_FRAME_STRING = "Fix control frame";
00053 
00054 Trajectory::Trajectory(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00055                        const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00056                        const GripperMarker::GripperMarkerState &state, unsigned int nwaypoints, bool is_selected, bool visible_x, bool visible_y, bool visible_z):
00057                        dragging_(false), nwaypoints_(nwaypoints), control_marker_mode_(CONTROL_MARKER_FIXED)
00058 {
00059   createControlMarker(robot_state, parent_node, context, name, frame_id, eef, pose, scale, state, is_selected, visible_x, visible_y, visible_z);
00060   createHandMarker();
00061 }
00062 
00063 void Trajectory::createControlMarker(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00064                        const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00065                        const GripperMarker::GripperMarkerState &state, bool is_selected, bool visible_x, bool visible_y, bool visible_z)
00066 {
00067   GripperMarkerPtr control( new GripperMarker(robot_state, parent_node, context, name, frame_id, eef, pose, scale, state));
00068   control->select(true);
00069   std::vector<visualization_msgs::MenuEntry> menu_entries;
00070   visualization_msgs::MenuEntry m;
00071   m.id = TRAJECTORY_SET_START_POSE;
00072   m.command_type = m.FEEDBACK;
00073   m.parent_id = 0;
00074   m.title = TRAJECTORY_SET_START_POSE_STRING;
00075   menu_entries.push_back(m);
00076   m.id = TRAJECTORY_SET_END_POSE;
00077   m.command_type = m.FEEDBACK;
00078   m.parent_id = 0;
00079   m.title = TRAJECTORY_SET_END_POSE_STRING;
00080   menu_entries.push_back(m);
00081   m.id = TRAJECTORY_EDIT_CONTROL_FRAME;
00082   m.command_type = m.FEEDBACK;
00083   m.parent_id = 0;
00084   m.title = TRAJECTORY_EDIT_CONTROL_FRAME_STRING;
00085   menu_entries.push_back(m);
00086   control->setMenu(menu_entries);
00087   control->select(false);
00088 
00089   control_marker = control;
00090   connectControlMarker();
00091 }
00092 
00093 void Trajectory::createHandMarker()
00094 {
00095   if (control_marker)
00096   {
00097     hand_marker = GripperMarkerPtr(new GripperMarker(*control_marker));
00098     hand_marker->unselect(true);
00099     connectHandMarker();
00100   }
00101   else
00102   {
00103     ROS_ERROR("Main trajectory marker does not exist");
00104   }
00105 }
00106 
00107 void Trajectory::createStartMarker()
00108 {
00109   if (control_marker)
00110   {
00111     start_marker = GripperMarkerPtr(new GripperMarker(*hand_marker));
00112     start_marker->unselect(true);
00113     start_marker->setColor(0.0, 0.9, 0.0, 1.0);
00114     start_marker->showDescription("Start");
00115     connectStartMarker();
00116   }
00117   else
00118   {
00119     ROS_ERROR("Main trajectory marker does not exist");
00120   }
00121 }
00122 
00123 void Trajectory::createEndMarker()
00124 {
00125   if (control_marker)
00126   {
00127     end_marker = GripperMarkerPtr(new GripperMarker(*hand_marker));
00128     end_marker->unselect(true);
00129     end_marker->setColor(0.0, 0.9, 0.0, 0.5);
00130     end_marker->showDescription("End");
00131     connectEndMarker();
00132   }
00133   else
00134   {
00135     ROS_ERROR("Main trajectory marker does not exist");
00136   }
00137 }
00138 
00139 void Trajectory::connectControlMarker()
00140 {
00141   control_marker->connect(this, SLOT( trajectoryMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &)));
00142 }
00143 
00144 void Trajectory::connectHandMarker()
00145 {
00146   hand_marker->connect( this, SLOT( handMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &) ));
00147 }
00148 
00149 void Trajectory::connectStartMarker()
00150 {
00151   start_marker->connect(this, SLOT( startMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &) ));
00152 }
00153 void Trajectory::connectEndMarker()
00154 {
00155   end_marker->connect(this, SLOT( endMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &) ));
00156 }
00157 
00158 void Trajectory::rebuildWayPointMarkers()
00159 {
00160   waypoint_markers.clear();
00161   if (start_marker && end_marker)
00162   {
00163     Eigen::Vector3d start_t(control_marker_start_pose.translation());
00164     Eigen::Vector3d end_t(control_marker_end_pose.translation());
00165 
00166     Eigen::Quaterniond start_r(control_marker_start_pose.rotation());
00167     Eigen::Quaterniond end_r(control_marker_end_pose.rotation());
00168 
00169     Eigen::Affine3d wMh;
00170     hand_marker->getPose(wMh);
00171 
00172     Eigen::Affine3d wMt;
00173     control_marker->getPose(wMt);
00174 
00175     Eigen::Affine3d tMh = wMt.inverse() * wMh;
00176 
00177     unsigned int nfragments = nwaypoints_ + 1;
00178     for (std::size_t i = 0; i <= nfragments; ++i)
00179     {
00180       Eigen::Vector3d waypoint_t = ((nfragments - i) * start_t + i * end_t) / nfragments;
00181       Eigen::Quaterniond waypoint_r = start_r.slerp( (double)i / (double)nfragments, end_r );
00182       Eigen::Affine3d wMwpt(waypoint_r);
00183       wMwpt.translation() = waypoint_t;
00184 
00185       Eigen::Affine3d wMwph = wMwpt * tMh;
00186 
00187       GripperMarkerPtr waypoint(new GripperMarker(*hand_marker));
00188       std::stringstream name;
00189       name << hand_marker->getName() << "_wp" << i;
00190       waypoint->setName(name.str());
00191       waypoint->unselect(true);
00192       waypoint->setColor(0.0, 0.9, 0.0, 1 - (double)i / (double)nfragments);
00193       Eigen::Quaterniond rotation(wMwph.rotation());
00194       waypoint->imarker->setPose(Ogre::Vector3(wMwph(0,3), wMwph(1,3), wMwph(2,3)),
00195                                  Ogre::Quaternion(rotation.w(), rotation.x(), rotation.y(), rotation.z()), "");
00196       waypoint_markers.push_back(waypoint);
00197     }
00198   }
00199 }
00200 
00201 void Trajectory::trajectoryMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00202 {
00203   if (feedback.event_type == feedback.MENU_SELECT)
00204   {
00205     if (feedback.menu_entry_id == TRAJECTORY_SET_START_POSE)
00206     {
00207       if (control_marker_mode_ == CONTROL_MARKER_FLOATING)
00208       {
00209         //If the control marker is not fixed, fix it
00210         fixControlFrame();
00211       }
00212 
00213       control_marker->getPose(control_marker_start_pose);
00214 
00215       //Create start marker
00216       JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::createStartMarker, this));
00217       JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::rebuildWayPointMarkers, this));
00218     }
00219     else if (feedback.menu_entry_id == TRAJECTORY_SET_END_POSE)
00220     {
00221       if (control_marker_mode_ == CONTROL_MARKER_FLOATING)
00222       {
00223         //If the control marker is not fixed, fix it
00224         fixControlFrame();
00225       }
00226 
00227       control_marker->getPose(control_marker_end_pose);
00228 
00229       //Create end marker
00230       JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::createEndMarker, this));
00231       JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::rebuildWayPointMarkers, this));
00232     }
00233     else if (feedback.menu_entry_id == TRAJECTORY_EDIT_CONTROL_FRAME)
00234     {
00235       editControlFrame();
00236     }
00237     else if (feedback.menu_entry_id == TRAJECTORY_FIX_CONTROL_FRAME)
00238     {
00239       fixControlFrame();
00240     }
00241   }
00242   else if (feedback.event_type == feedback.MOUSE_DOWN && control_marker_mode_ == CONTROL_MARKER_FIXED)
00243   {
00244     //Store current hand pose
00245     hand_marker->getPose(hand_marker_start_pose);
00246     control_marker->getPose(control_marker_drag_start_pose);
00247 
00248     dragging_=true;
00249   }
00250   else if (feedback.event_type == feedback.POSE_UPDATE && dragging_ && control_marker_mode_ == CONTROL_MARKER_FIXED)
00251   {
00252     //Compute displacement from stored pose, and apply to the rest of selected markers
00253     Eigen::Affine3d current_pose_eigen;
00254     tf::poseMsgToEigen(feedback.pose, current_pose_eigen);
00255 
00256     Eigen::Affine3d current_wrt_initial = control_marker_drag_start_pose.inverse() * current_pose_eigen;
00257 
00258     visualization_msgs::InteractiveMarkerPose impose;
00259     Eigen::Affine3d newpose = control_marker_drag_start_pose * current_wrt_initial * control_marker_drag_start_pose.inverse() * hand_marker_start_pose;
00260     tf::poseEigenToMsg(newpose, impose.pose);
00261 
00262     hand_marker->imarker->setPose(Ogre::Vector3(impose.pose.position.x, impose.pose.position.y, impose.pose.position.z),
00263                                   Ogre::Quaternion(impose.pose.orientation.w, impose.pose.orientation.x, impose.pose.orientation.y, impose.pose.orientation.z), "");
00264   }
00265   else if (feedback.event_type == feedback.MOUSE_UP)
00266   {
00267     dragging_ = false;
00268   }
00269 }
00270 
00271 void Trajectory::editControlFrame()
00272 {
00273   start_marker.reset();
00274   end_marker.reset();
00275   waypoint_markers.clear();
00276 
00277   control_marker_mode_ = CONTROL_MARKER_FLOATING;
00278 
00279   std::vector<visualization_msgs::MenuEntry> menu_entries;
00280   visualization_msgs::MenuEntry m;
00281   m.id = TRAJECTORY_SET_START_POSE;
00282   m.command_type = m.FEEDBACK;
00283   m.parent_id = 0;
00284   m.title = TRAJECTORY_SET_START_POSE_STRING;
00285   menu_entries.push_back(m);
00286   m.id = TRAJECTORY_SET_END_POSE;
00287   m.command_type = m.FEEDBACK;
00288   m.parent_id = 0;
00289   m.title = TRAJECTORY_SET_END_POSE_STRING;
00290   menu_entries.push_back(m);
00291   m.id = TRAJECTORY_FIX_CONTROL_FRAME;
00292   m.command_type = m.FEEDBACK;
00293   m.parent_id = 0;
00294   m.title = TRAJECTORY_FIX_CONTROL_FRAME_STRING;
00295   menu_entries.push_back(m);
00296 
00297   JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::GripperMarker::setMenu, control_marker, menu_entries));
00298   JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::connectControlMarker, this));
00299 }
00300 
00301 void Trajectory::fixControlFrame()
00302 {
00303   control_marker_mode_ = CONTROL_MARKER_FIXED;
00304 
00305   std::vector<visualization_msgs::MenuEntry> menu_entries;
00306   visualization_msgs::MenuEntry m;
00307   m.id = TRAJECTORY_SET_START_POSE;
00308   m.command_type = m.FEEDBACK;
00309   m.parent_id = 0;
00310   m.title = TRAJECTORY_SET_START_POSE_STRING;
00311   menu_entries.push_back(m);
00312   m.id = TRAJECTORY_SET_END_POSE;
00313   m.command_type = m.FEEDBACK;
00314   m.parent_id = 0;
00315   m.title = TRAJECTORY_SET_END_POSE_STRING;
00316   menu_entries.push_back(m);
00317   m.id = TRAJECTORY_EDIT_CONTROL_FRAME;
00318   m.command_type = m.FEEDBACK;
00319   m.parent_id = 0;
00320   m.title = TRAJECTORY_EDIT_CONTROL_FRAME_STRING;
00321   menu_entries.push_back(m);
00322 
00323   JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::GripperMarker::setMenu, control_marker, menu_entries));
00324   JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::connectControlMarker, this));
00325 }
00326 
00327 void Trajectory::startMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00328 {
00329 }
00330 
00331 void Trajectory::endMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00332 {
00333 }
00334 
00335 void Trajectory::handMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00336 {
00337 }
00338 
00339 } //namespace


benchmarks_gui
Author(s): Mario Prats
autogenerated on Wed Aug 26 2015 12:44:27