Go to the documentation of this file.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 
00033 
00034 
00035 
00036 
00037 #ifndef MOVEIT_ROBOT_INTERACTION_INTERACTION_HANDLER_
00038 #define MOVEIT_ROBOT_INTERACTION_INTERACTION_HANDLER_
00039 
00040 #include <moveit/macros/class_forward.h>
00041 #include <moveit/robot_interaction/locked_robot_state.h>
00042 
00043 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00044 #include <interactive_markers/menu_handler.h>
00045 #include <tf/tf.h>
00046 
00047 namespace robot_interaction
00048 {
00049 MOVEIT_CLASS_FORWARD(InteractionHandler);
00050 MOVEIT_CLASS_FORWARD(RobotInteraction);
00051 MOVEIT_CLASS_FORWARD(KinematicOptionsMap);
00052 
00053 class EndEffectorInteraction;
00054 class JointInteraction;
00055 class GenericInteraction;
00056 
00066 typedef boost::function<void(InteractionHandler*, bool)> InteractionHandlerCallbackFn;
00067 
00076 class InteractionHandler : public LockedRobotState
00077 {
00078 public:
00079   
00080   InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
00081                      const robot_state::RobotState& initial_robot_state,
00082                      const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>());
00083 
00084   
00085   InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
00086                      const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>());
00087 
00088   
00089   InteractionHandler(const std::string& name, const robot_state::RobotState& initial_robot_state,
00090                      const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>());
00091   
00092   InteractionHandler(const std::string& name, const robot_model::RobotModelConstPtr& model,
00093                      const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>());
00094 
00095   virtual ~InteractionHandler()
00096   {
00097   }
00098 
00099   const std::string& getName() const
00100   {
00101     return name_;
00102   }
00103 
00105   using LockedRobotState::getState;
00106 
00108   using LockedRobotState::setState;
00109 
00110   void setUpdateCallback(const InteractionHandlerCallbackFn& callback);
00111   const InteractionHandlerCallbackFn& getUpdateCallback() const;
00112   void setMeshesVisible(bool visible);
00113   bool getMeshesVisible() const;
00114   void setControlsVisible(bool visible);
00115   bool getControlsVisible() const;
00116 
00120   void setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::Pose& m);
00121 
00125   void setPoseOffset(const JointInteraction& j, const geometry_msgs::Pose& m);
00126 
00131   bool getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::Pose& m);
00132 
00137   bool getPoseOffset(const JointInteraction& vj, geometry_msgs::Pose& m);
00138 
00142   void clearPoseOffset(const EndEffectorInteraction& eef);
00143 
00146   void clearPoseOffset(const JointInteraction& vj);
00147 
00149   void clearPoseOffsets();
00150 
00154   void setMenuHandler(const boost::shared_ptr<interactive_markers::MenuHandler>& mh);
00155 
00159   const boost::shared_ptr<interactive_markers::MenuHandler>& getMenuHandler();
00160 
00162   void clearMenuHandler();
00163 
00169   bool getLastEndEffectorMarkerPose(const EndEffectorInteraction& eef, geometry_msgs::PoseStamped& pose);
00170 
00176   bool getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::PoseStamped& pose);
00177 
00181   void clearLastEndEffectorMarkerPose(const EndEffectorInteraction& eef);
00182 
00185   void clearLastJointMarkerPose(const JointInteraction& vj);
00186 
00189   void clearLastMarkerPoses();
00190 
00193   virtual void handleEndEffector(const EndEffectorInteraction& eef,
00194                                  const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00195 
00198   virtual void handleJoint(const JointInteraction& vj,
00199                            const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00200 
00203   virtual void handleGeneric(const GenericInteraction& g,
00204                              const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00205 
00208   virtual bool inError(const EndEffectorInteraction& eef) const;
00209 
00212   virtual bool inError(const JointInteraction& vj) const;
00213 
00215   virtual bool inError(const GenericInteraction& g) const;
00216 
00219   void clearError(void);
00220 
00224   void setRobotInteraction(RobotInteraction* robot_interaction);
00225 
00226 protected:
00227   bool transformFeedbackPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback,
00228                              const geometry_msgs::Pose& offset, geometry_msgs::PoseStamped& tpose);
00229 
00230   const std::string name_;
00231   const std::string planning_frame_;
00232   boost::shared_ptr<tf::Transformer> tf_;
00233 
00234 private:
00235   typedef boost::function<void(InteractionHandler*)> StateChangeCallbackFn;
00236 
00237   
00238   
00239   void updateStateGeneric(robot_state::RobotState* state, const GenericInteraction* g,
00240                           const visualization_msgs::InteractiveMarkerFeedbackConstPtr* feedback,
00241                           StateChangeCallbackFn* callback);
00242 
00243   
00244   
00245   void updateStateEndEffector(robot_state::RobotState* state, const EndEffectorInteraction* eef,
00246                               const geometry_msgs::Pose* pose, StateChangeCallbackFn* callback);
00247 
00248   
00249   
00250   void updateStateJoint(robot_state::RobotState* state, const JointInteraction* vj, const geometry_msgs::Pose* pose,
00251                         StateChangeCallbackFn* callback);
00252 
00253   
00254   
00255   
00256   bool setErrorState(const std::string& name, bool new_error_state);
00257 
00260   bool getErrorState(const std::string& name) const;
00261 
00262   
00263   
00264   
00265   
00266   
00267   
00268   
00269   std::map<std::string, geometry_msgs::Pose> offset_map_;
00270 
00271   
00272   
00273   
00274   
00275   
00276   
00277   
00278   std::map<std::string, geometry_msgs::PoseStamped> pose_map_;
00279 
00280   
00281   
00282   
00283   
00284   
00285   
00286   
00287   const void* robot_interaction_;
00288 
00289   boost::mutex pose_map_lock_;
00290   boost::mutex offset_map_lock_;
00291 
00292   
00293   
00294   
00295   KinematicOptionsMapPtr kinematic_options_map_;
00296 
00297   
00298   
00299   std::set<std::string> error_state_;
00300 
00301   
00302   
00303   
00304   
00305   
00306   boost::shared_ptr<interactive_markers::MenuHandler> menu_handler_;
00307 
00308   
00309   
00310   
00311   
00312   
00313   
00314   
00315   
00316   boost::function<void(InteractionHandler* handler, bool error_state_changed)> update_callback_;
00317 
00318   
00319   bool display_meshes_;
00320 
00321   
00322   bool display_controls_;
00323 
00324   
00325   static std::string fixName(std::string name);
00326 
00327 public:
00328   
00329   
00330   
00331   void setGroupStateValidityCallback(const robot_state::GroupStateValidityCallbackFn& callback);
00332   void setIKTimeout(double timeout);
00333   void setIKAttempts(unsigned int attempts);
00334   kinematics::KinematicsQueryOptions getKinematicsQueryOptions() const;
00335   void setKinematicsQueryOptions(const kinematics::KinematicsQueryOptions& opt);
00336   void setKinematicsQueryOptionsForGroup(const std::string& group_name,
00337                                          const kinematics::KinematicsQueryOptions& options);
00338 };
00339 }
00340 
00341 #endif