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
00037 #ifndef PLANNING_ENVIRONMENT_MONITORS_KINEMATIC_MODEL_STATE_MONITOR_
00038 #define PLANNING_ENVIRONMENT_MONITORS_KINEMATIC_MODEL_STATE_MONITOR_
00039
00040 #include "planning_environment/models/robot_models.h"
00041 #include <tf/transform_datatypes.h>
00042 #include <tf/transform_listener.h>
00043 #include <tf/message_filter.h>
00044 #include <message_filters/subscriber.h>
00045 #include <sensor_msgs/JointState.h>
00046 #include <motion_planning_msgs/RobotState.h>
00047 #include <boost/bind.hpp>
00048 #include <vector>
00049 #include <string>
00050 #include <map>
00051 #include <planning_models/kinematic_state.h>
00052
00053 namespace planning_environment
00054 {
00055
00060 class KinematicModelStateMonitor
00061 {
00062 public:
00063
00064 KinematicModelStateMonitor(RobotModels *rm, tf::TransformListener *tf) : nh_("~")
00065 {
00066 rm_ = rm;
00067 tf_ = tf;
00068 setupRSM();
00069 }
00070
00071 virtual ~KinematicModelStateMonitor(void)
00072 {
00073 }
00074
00076 void startStateMonitor(void);
00077
00079 void stopStateMonitor(void);
00080
00082 bool isStateMonitorStarted(void) const
00083 {
00084 return stateMonitorStarted_;
00085 }
00086
00088 virtual void advertiseServices() {
00089
00090 }
00091
00092
00094 void setOnStateUpdateCallback(const boost::function<void(void)> &callback)
00095 {
00096 onStateUpdate_ = callback;
00097 }
00098
00100 boost::shared_ptr<planning_models::KinematicModel> getKinematicModel(void) const
00101 {
00102 return kmodel_;
00103 }
00104
00106 RobotModels* getRobotModels(void) const
00107 {
00108 return rm_;
00109 }
00110
00112 double getTotalVelocity(void) const
00113 {
00114 return robotVelocity_;
00115 }
00116
00118 tf::TransformListener *getTransformListener(void) const
00119 {
00120 return tf_;
00121 }
00122
00124 const std::string& getRobotFrameId(void) const
00125 {
00126 return robot_frame_;
00127 }
00128
00130 const std::string& getWorldFrameId(void) const
00131 {
00132 return kmodel_->getRoot()->getParentFrameId();
00133 }
00134
00136 bool haveState(void) const
00137 {
00138 return haveJointState_ && havePose_;
00139 }
00140
00142 const ros::Time& lastJointStateUpdate(void) const
00143 {
00144 return lastJointStateUpdate_;
00145 }
00146
00148 const ros::Time& lastPoseUpdate(void) const
00149 {
00150 return lastPoseUpdate_;
00151 }
00152
00154 void waitForState(void) const;
00155
00157 bool isJointStateUpdated(double sec) const;
00158
00162 bool isPoseUpdated(double sec) const;
00163
00165 void printRobotState(void) const;
00166
00168 void setStateValuesFromCurrentValues(planning_models::KinematicState& state) const;
00169
00170 void setRobotStateAndComputeTransforms(const motion_planning_msgs::RobotState &robot_state,
00171 planning_models::KinematicState& state) const;
00172
00173 bool getCurrentRobotState(motion_planning_msgs::RobotState &robot_state) const;
00174
00175 bool setKinematicStateToTime(const ros::Time& time,
00176 planning_models::KinematicState& state) const;
00177
00178 bool convertKinematicStateToRobotState(const planning_models::KinematicState& state,
00179 motion_planning_msgs::RobotState &robot_state) const;
00180
00181 bool getCachedJointStateValues(const ros::Time& time, std::map<std::string, double>& ret_map) const;
00182
00183 bool allJointsUpdated(ros::Duration dur = ros::Duration()) const;
00184
00185
00186 std::map<std::string, double> getCurrentJointStateValues() const {
00187 current_joint_values_lock_.lock();
00188 std::map<std::string, double> ret_values = current_joint_state_map_;
00189 current_joint_values_lock_.unlock();
00190 return ret_values;
00191 }
00192
00193 protected:
00194
00195 void setupRSM(void);
00196 void jointStateCallback(const sensor_msgs::JointStateConstPtr &jointState);
00197
00198 std::list<std::pair<ros::Time, std::map<std::string, double> > >joint_state_map_cache_;
00199
00200 std::map<std::string, ros::Time> last_joint_update_;
00201 std::map<std::string, double> current_joint_state_map_;
00202
00203 mutable boost::recursive_mutex current_joint_values_lock_;
00204
00205 double joint_state_cache_time_;
00206 double joint_state_cache_allowed_difference_;
00207
00208 RobotModels *rm_;
00209
00210 boost::shared_ptr<planning_models::KinematicModel> kmodel_;
00211 std::string planarJoint_;
00212 std::string floatingJoint_;
00213
00214 bool stateMonitorStarted_;
00215 bool printed_out_of_date_;
00216
00217 ros::NodeHandle nh_;
00218 ros::NodeHandle root_handle_;
00219 ros::Subscriber jointStateSubscriber_;
00220 tf::TransformListener *tf_;
00221
00222 double robotVelocity_;
00223 tf::Pose pose_;
00224 std::string robot_frame_;
00225
00226 boost::function<void(void)> onStateUpdate_;
00227
00228 bool havePose_;
00229 bool haveJointState_;
00230 ros::Time lastJointStateUpdate_;
00231 ros::Time lastPoseUpdate_;
00232 };
00233
00234 }
00235
00236 #endif