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/robot_interaction/locked_robot_state.h>
00041
00042 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00043 #include <interactive_markers/menu_handler.h>
00044 #include <tf/tf.h>
00045
00046 namespace robot_interaction
00047 {
00048
00049 class InteractionHandler;
00050 typedef boost::shared_ptr<InteractionHandler> InteractionHandlerPtr;
00051 typedef boost::shared_ptr<const InteractionHandler> InteractionHandlerConstPtr;
00052
00053 class RobotInteraction;
00054 typedef boost::shared_ptr<RobotInteraction> RobotInteractionPtr;
00055
00056 class KinematicOptionsMap;
00057 typedef boost::shared_ptr<KinematicOptionsMap> KinematicOptionsMapPtr;
00058
00059 class EndEffectorInteraction;
00060 class JointInteraction;
00061 class GenericInteraction;
00062
00063
00073 typedef boost::function<void(InteractionHandler*, bool)> InteractionHandlerCallbackFn;
00074
00075
00076
00085 class InteractionHandler : public LockedRobotState
00086 {
00087 public:
00088
00089 InteractionHandler(const RobotInteractionPtr& robot_interaction,
00090 const std::string &name,
00091 const robot_state::RobotState &initial_robot_state,
00092 const boost::shared_ptr<tf::Transformer> &tf = boost::shared_ptr<tf::Transformer>());
00093
00094
00095 InteractionHandler(const RobotInteractionPtr& robot_interaction,
00096 const std::string &name,
00097 const boost::shared_ptr<tf::Transformer> &tf = boost::shared_ptr<tf::Transformer>());
00098
00099
00100 InteractionHandler(const std::string &name,
00101 const robot_state::RobotState &initial_robot_state,
00102 const boost::shared_ptr<tf::Transformer> &tf = boost::shared_ptr<tf::Transformer>());
00103
00104 InteractionHandler(const std::string &name,
00105 const robot_model::RobotModelConstPtr &model,
00106 const boost::shared_ptr<tf::Transformer> &tf = boost::shared_ptr<tf::Transformer>());
00107
00108 virtual ~InteractionHandler()
00109 {
00110 }
00111
00112 const std::string& getName() const
00113 {
00114 return name_;
00115 }
00116
00118 using LockedRobotState::getState;
00119
00121 using LockedRobotState::setState;
00122
00123 void setUpdateCallback(const InteractionHandlerCallbackFn &callback);
00124 const InteractionHandlerCallbackFn& getUpdateCallback() const;
00125 void setMeshesVisible(bool visible);
00126 bool getMeshesVisible() const;
00127 void setControlsVisible(bool visible);
00128 bool getControlsVisible() const;
00129
00133 void setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::Pose& m);
00134
00138 void setPoseOffset(const JointInteraction& j, const geometry_msgs::Pose& m);
00139
00144 bool getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::Pose& m);
00145
00150 bool getPoseOffset(const JointInteraction& vj, geometry_msgs::Pose& m);
00151
00155 void clearPoseOffset(const EndEffectorInteraction& eef);
00156
00159 void clearPoseOffset(const JointInteraction& vj);
00160
00162 void clearPoseOffsets();
00163
00167 void setMenuHandler(
00168 const boost::shared_ptr<interactive_markers::MenuHandler>& mh);
00169
00170
00174 const boost::shared_ptr<interactive_markers::MenuHandler>& getMenuHandler();
00175
00177 void clearMenuHandler();
00178
00184 bool getLastEndEffectorMarkerPose(const EndEffectorInteraction& eef,
00185 geometry_msgs::PoseStamped& pose);
00186
00192 bool getLastJointMarkerPose(const JointInteraction& vj,
00193 geometry_msgs::PoseStamped& pose);
00194
00198 void clearLastEndEffectorMarkerPose(const EndEffectorInteraction& eef);
00199
00202 void clearLastJointMarkerPose(const JointInteraction& vj);
00203
00206 void clearLastMarkerPoses();
00207
00210 virtual void handleEndEffector(
00211 const EndEffectorInteraction &eef,
00212 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00213
00216 virtual void handleJoint(
00217 const JointInteraction &vj,
00218 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00219
00222 virtual void handleGeneric(
00223 const GenericInteraction &g,
00224 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00225
00228 virtual bool inError(const EndEffectorInteraction& eef) const;
00229
00232 virtual bool inError(const JointInteraction& vj) const;
00233
00235 virtual bool inError(const GenericInteraction& g) const;
00236
00239 void clearError(void);
00240
00244 void setRobotInteraction(RobotInteraction* robot_interaction);
00245
00246 protected:
00247
00248 bool transformFeedbackPose(
00249 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback,
00250 const geometry_msgs::Pose &offset,
00251 geometry_msgs::PoseStamped &tpose);
00252
00253 const std::string name_;
00254 const std::string planning_frame_;
00255 boost::shared_ptr<tf::Transformer> tf_;
00256
00257 private:
00258
00259 typedef boost::function<void(InteractionHandler*)> StateChangeCallbackFn;
00260
00261
00262
00263 void updateStateGeneric(
00264 robot_state::RobotState* state,
00265 const GenericInteraction* g,
00266 const visualization_msgs::InteractiveMarkerFeedbackConstPtr *feedback,
00267 StateChangeCallbackFn *callback);
00268
00269
00270
00271 void updateStateEndEffector(robot_state::RobotState* state,
00272 const EndEffectorInteraction* eef,
00273 const geometry_msgs::Pose* pose,
00274 StateChangeCallbackFn *callback);
00275
00276
00277
00278 void updateStateJoint(robot_state::RobotState* state,
00279 const JointInteraction* vj,
00280 const geometry_msgs::Pose* pose,
00281 StateChangeCallbackFn *callback);
00282
00283
00284
00285
00286 bool setErrorState(const std::string& name, bool new_error_state);
00287
00290 bool getErrorState(const std::string& name) const;
00291
00292
00293
00294
00295
00296
00297
00298
00299 std::map<std::string, geometry_msgs::Pose> offset_map_;
00300
00301
00302
00303
00304
00305
00306
00307
00308 std::map<std::string, geometry_msgs::PoseStamped> pose_map_;
00309
00310
00311
00312
00313
00314
00315
00316
00317 const void* robot_interaction_;
00318
00319 boost::mutex pose_map_lock_;
00320 boost::mutex offset_map_lock_;
00321
00322
00323
00324
00325 KinematicOptionsMapPtr kinematic_options_map_;
00326
00327
00328
00329 std::set<std::string> error_state_;
00330
00331
00332
00333
00334
00335
00336 boost::shared_ptr<interactive_markers::MenuHandler> menu_handler_;
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346 boost::function<void(InteractionHandler* handler,
00347 bool error_state_changed)> update_callback_;
00348
00349
00350 bool display_meshes_;
00351
00352
00353 bool display_controls_;
00354
00355
00356 static std::string fixName(std::string name);
00357
00358 public:
00359
00360
00361
00362 void setGroupStateValidityCallback(
00363 const robot_state::GroupStateValidityCallbackFn &callback);
00364 void setIKTimeout(double timeout);
00365 void setIKAttempts(unsigned int attempts);
00366 const kinematics::KinematicsQueryOptions& getKinematicsQueryOptions() const;
00367 void setKinematicsQueryOptions(const kinematics::KinematicsQueryOptions &opt);
00368 void setKinematicsQueryOptionsForGroup(const std::string& group_name,
00369 const kinematics::KinematicsQueryOptions &options);
00370 };
00371
00372
00373 }
00374
00375 #endif