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
00031
00032 #include <trajectory.h>
00033 #include <job_processing.h>
00034
00035 #include <eigen_conversions/eigen_msg.h>
00036
00037 #include <boost/math/constants/constants.hpp>
00038
00039 #include <QWidget>
00040
00041 namespace benchmark_tool
00042 {
00043
00044 const std::string Trajectory::TRAJECTORY_SET_START_POSE_STRING = "Set start pose";
00045 const std::string Trajectory::TRAJECTORY_SET_END_POSE_STRING = "Set end pose";
00046 const std::string Trajectory::TRAJECTORY_EDIT_CONTROL_FRAME_STRING = "Edit control frame";
00047 const std::string Trajectory::TRAJECTORY_FIX_CONTROL_FRAME_STRING = "Fix control frame";
00048
00049 Trajectory::Trajectory(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00050 const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00051 const GripperMarker::GripperMarkerState &state, unsigned int nwaypoints, bool is_selected, bool visible_x, bool visible_y, bool visible_z):
00052 dragging_(false), control_marker_mode_(CONTROL_MARKER_FIXED), nwaypoints_(nwaypoints)
00053 {
00054 createControlMarker(robot_state, parent_node, context, name, frame_id, eef, pose, scale, state, is_selected, visible_x, visible_y, visible_z);
00055 createHandMarker();
00056 }
00057
00058 void Trajectory::createControlMarker(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00059 const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00060 const GripperMarker::GripperMarkerState &state, bool is_selected, bool visible_x, bool visible_y, bool visible_z)
00061 {
00062 GripperMarkerPtr control( new GripperMarker(robot_state, parent_node, context, name, frame_id, eef, pose, scale, state));
00063 control->select(true);
00064 std::vector<visualization_msgs::MenuEntry> menu_entries;
00065 visualization_msgs::MenuEntry m;
00066 m.id = TRAJECTORY_SET_START_POSE;
00067 m.command_type = m.FEEDBACK;
00068 m.parent_id = 0;
00069 m.title = TRAJECTORY_SET_START_POSE_STRING;
00070 menu_entries.push_back(m);
00071 m.id = TRAJECTORY_SET_END_POSE;
00072 m.command_type = m.FEEDBACK;
00073 m.parent_id = 0;
00074 m.title = TRAJECTORY_SET_END_POSE_STRING;
00075 menu_entries.push_back(m);
00076 m.id = TRAJECTORY_EDIT_CONTROL_FRAME;
00077 m.command_type = m.FEEDBACK;
00078 m.parent_id = 0;
00079 m.title = TRAJECTORY_EDIT_CONTROL_FRAME_STRING;
00080 menu_entries.push_back(m);
00081 control->setMenu(menu_entries);
00082 control->select(false);
00083
00084 control_marker = control;
00085 connectControlMarker();
00086 }
00087
00088 void Trajectory::createHandMarker()
00089 {
00090 if (control_marker)
00091 {
00092 hand_marker = GripperMarkerPtr(new GripperMarker(*control_marker));
00093 hand_marker->unselect(true);
00094 connectHandMarker();
00095 }
00096 else
00097 {
00098 ROS_ERROR("Main trajectory marker does not exist");
00099 }
00100 }
00101
00102 void Trajectory::createStartMarker()
00103 {
00104 if (control_marker)
00105 {
00106 start_marker = GripperMarkerPtr(new GripperMarker(*hand_marker));
00107 start_marker->unselect(true);
00108 start_marker->setColor(0.0, 0.9, 0.0, 1.0);
00109 start_marker->showDescription("Start");
00110 connectStartMarker();
00111 }
00112 else
00113 {
00114 ROS_ERROR("Main trajectory marker does not exist");
00115 }
00116 }
00117
00118 void Trajectory::createEndMarker()
00119 {
00120 if (control_marker)
00121 {
00122 end_marker = GripperMarkerPtr(new GripperMarker(*hand_marker));
00123 end_marker->unselect(true);
00124 end_marker->setColor(0.0, 0.9, 0.0, 0.5);
00125 end_marker->showDescription("End");
00126 connectEndMarker();
00127 }
00128 else
00129 {
00130 ROS_ERROR("Main trajectory marker does not exist");
00131 }
00132 }
00133
00134 void Trajectory::connectControlMarker()
00135 {
00136 control_marker->connect(this, SLOT( trajectoryMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &)));
00137 }
00138
00139 void Trajectory::connectHandMarker()
00140 {
00141 hand_marker->connect( this, SLOT( handMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &) ));
00142 }
00143
00144 void Trajectory::connectStartMarker()
00145 {
00146 start_marker->connect(this, SLOT( startMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &) ));
00147 }
00148 void Trajectory::connectEndMarker()
00149 {
00150 end_marker->connect(this, SLOT( endMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &) ));
00151 }
00152
00153 void Trajectory::rebuildWayPointMarkers()
00154 {
00155 waypoint_markers.clear();
00156 if (start_marker && end_marker)
00157 {
00158 Eigen::Vector3d start_t(control_marker_start_pose.translation());
00159 Eigen::Vector3d end_t(control_marker_end_pose.translation());
00160
00161 Eigen::Quaterniond start_r(control_marker_start_pose.rotation());
00162 Eigen::Quaterniond end_r(control_marker_end_pose.rotation());
00163
00164 Eigen::Affine3d wMh;
00165 hand_marker->getPose(wMh);
00166
00167 Eigen::Affine3d wMt;
00168 control_marker->getPose(wMt);
00169
00170 Eigen::Affine3d tMh = wMt.inverse() * wMh;
00171
00172 unsigned int nfragments = nwaypoints_ + 1;
00173 for (std::size_t i = 0; i <= nfragments; ++i)
00174 {
00175 Eigen::Vector3d waypoint_t = ((nfragments - i) * start_t + i * end_t) / nfragments;
00176 Eigen::Quaterniond waypoint_r = start_r.slerp( (double)i / (double)nfragments, end_r );
00177 Eigen::Affine3d wMwpt(waypoint_r);
00178 wMwpt.translation() = waypoint_t;
00179
00180 Eigen::Affine3d wMwph = wMwpt * tMh;
00181
00182 GripperMarkerPtr waypoint(new GripperMarker(*hand_marker));
00183 std::stringstream name;
00184 name << hand_marker->getName() << "_wp" << i;
00185 waypoint->setName(name.str());
00186 waypoint->unselect(true);
00187 waypoint->setColor(0.0, 0.9, 0.0, 1 - (double)i / (double)nfragments);
00188 Eigen::Quaterniond rotation(wMwph.rotation());
00189 waypoint->imarker->setPose(Ogre::Vector3(wMwph(0,3), wMwph(1,3), wMwph(2,3)),
00190 Ogre::Quaternion(rotation.w(), rotation.x(), rotation.y(), rotation.z()), "");
00191 waypoint_markers.push_back(waypoint);
00192 }
00193 }
00194 }
00195
00196 void Trajectory::trajectoryMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00197 {
00198 if (feedback.event_type == feedback.MENU_SELECT)
00199 {
00200 if (feedback.menu_entry_id == TRAJECTORY_SET_START_POSE)
00201 {
00202 if (control_marker_mode_ == CONTROL_MARKER_FLOATING)
00203 {
00204
00205 fixControlFrame();
00206 }
00207
00208 control_marker->getPose(control_marker_start_pose);
00209
00210
00211 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::createStartMarker, this));
00212 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::rebuildWayPointMarkers, this));
00213 }
00214 else if (feedback.menu_entry_id == TRAJECTORY_SET_END_POSE)
00215 {
00216 if (control_marker_mode_ == CONTROL_MARKER_FLOATING)
00217 {
00218
00219 fixControlFrame();
00220 }
00221
00222 control_marker->getPose(control_marker_end_pose);
00223
00224
00225 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::createEndMarker, this));
00226 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::rebuildWayPointMarkers, this));
00227 }
00228 else if (feedback.menu_entry_id == TRAJECTORY_EDIT_CONTROL_FRAME)
00229 {
00230 editControlFrame();
00231 }
00232 else if (feedback.menu_entry_id == TRAJECTORY_FIX_CONTROL_FRAME)
00233 {
00234 fixControlFrame();
00235 }
00236 }
00237 else if (feedback.event_type == feedback.MOUSE_DOWN && control_marker_mode_ == CONTROL_MARKER_FIXED)
00238 {
00239
00240 hand_marker->getPose(hand_marker_start_pose);
00241 control_marker->getPose(control_marker_drag_start_pose);
00242
00243 dragging_=true;
00244 }
00245 else if (feedback.event_type == feedback.POSE_UPDATE && dragging_ && control_marker_mode_ == CONTROL_MARKER_FIXED)
00246 {
00247
00248 Eigen::Affine3d current_pose_eigen;
00249 tf::poseMsgToEigen(feedback.pose, current_pose_eigen);
00250
00251 Eigen::Affine3d current_wrt_initial = control_marker_drag_start_pose.inverse() * current_pose_eigen;
00252
00253 visualization_msgs::InteractiveMarkerPose impose;
00254 Eigen::Affine3d newpose = control_marker_drag_start_pose * current_wrt_initial * control_marker_drag_start_pose.inverse() * hand_marker_start_pose;
00255 tf::poseEigenToMsg(newpose, impose.pose);
00256
00257 hand_marker->imarker->setPose(Ogre::Vector3(impose.pose.position.x, impose.pose.position.y, impose.pose.position.z),
00258 Ogre::Quaternion(impose.pose.orientation.w, impose.pose.orientation.x, impose.pose.orientation.y, impose.pose.orientation.z), "");
00259 }
00260 else if (feedback.event_type == feedback.MOUSE_UP)
00261 {
00262 dragging_ = false;
00263 }
00264 }
00265
00266 void Trajectory::editControlFrame()
00267 {
00268 start_marker.reset();
00269 end_marker.reset();
00270 waypoint_markers.clear();
00271
00272 control_marker_mode_ = CONTROL_MARKER_FLOATING;
00273
00274 std::vector<visualization_msgs::MenuEntry> menu_entries;
00275 visualization_msgs::MenuEntry m;
00276 m.id = TRAJECTORY_SET_START_POSE;
00277 m.command_type = m.FEEDBACK;
00278 m.parent_id = 0;
00279 m.title = TRAJECTORY_SET_START_POSE_STRING;
00280 menu_entries.push_back(m);
00281 m.id = TRAJECTORY_SET_END_POSE;
00282 m.command_type = m.FEEDBACK;
00283 m.parent_id = 0;
00284 m.title = TRAJECTORY_SET_END_POSE_STRING;
00285 menu_entries.push_back(m);
00286 m.id = TRAJECTORY_FIX_CONTROL_FRAME;
00287 m.command_type = m.FEEDBACK;
00288 m.parent_id = 0;
00289 m.title = TRAJECTORY_FIX_CONTROL_FRAME_STRING;
00290 menu_entries.push_back(m);
00291
00292 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::GripperMarker::setMenu, control_marker, menu_entries));
00293 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::connectControlMarker, this));
00294 }
00295
00296 void Trajectory::fixControlFrame()
00297 {
00298 control_marker_mode_ = CONTROL_MARKER_FIXED;
00299
00300 std::vector<visualization_msgs::MenuEntry> menu_entries;
00301 visualization_msgs::MenuEntry m;
00302 m.id = TRAJECTORY_SET_START_POSE;
00303 m.command_type = m.FEEDBACK;
00304 m.parent_id = 0;
00305 m.title = TRAJECTORY_SET_START_POSE_STRING;
00306 menu_entries.push_back(m);
00307 m.id = TRAJECTORY_SET_END_POSE;
00308 m.command_type = m.FEEDBACK;
00309 m.parent_id = 0;
00310 m.title = TRAJECTORY_SET_END_POSE_STRING;
00311 menu_entries.push_back(m);
00312 m.id = TRAJECTORY_EDIT_CONTROL_FRAME;
00313 m.command_type = m.FEEDBACK;
00314 m.parent_id = 0;
00315 m.title = TRAJECTORY_EDIT_CONTROL_FRAME_STRING;
00316 menu_entries.push_back(m);
00317
00318 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::GripperMarker::setMenu, control_marker, menu_entries));
00319 JobProcessing::addMainLoopJob(boost::bind(&benchmark_tool::Trajectory::connectControlMarker, this));
00320 }
00321
00322 void Trajectory::startMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00323 {
00324 }
00325
00326 void Trajectory::endMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00327 {
00328 }
00329
00330 void Trajectory::handMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
00331 {
00332 }
00333
00334 }