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 #ifndef JSK_FOOTSTEP_CONTROLLER_FOOTCOORDS_H_
00037 #define JSK_FOOTSTEP_CONTROLLER_FOOTCOORDS_H_
00038 #include <Eigen/Geometry>
00039 #include <sensor_msgs/Imu.h>
00040 #include <geometry_msgs/WrenchStamped.h>
00041 #include <tf/transform_listener.h>
00042 #include <diagnostic_updater/diagnostic_updater.h>
00043 #include <diagnostic_updater/publisher.h>
00044 #include <message_filters/subscriber.h>
00045 #include <message_filters/time_synchronizer.h>
00046 #include <message_filters/synchronizer.h>
00047 #include <tf/transform_listener.h>
00048 #include <tf/transform_broadcaster.h>
00049 #include <jsk_footstep_controller/GroundContactState.h>
00050 #include <jsk_footstep_controller/FootCoordsLowLevelInfo.h>
00051 #include <jsk_footstep_controller/SynchronizedForces.h>
00052 #include <std_msgs/Empty.h>
00053 #include <nav_msgs/Odometry.h>
00054 #include <urdf/model.h>
00055 #include <kdl/tree.hpp>
00056 #include <kdl/chainjnttojacsolver.hpp>
00057 #include <kdl_parser/kdl_parser.hpp>
00058
00059 namespace jsk_footstep_controller
00060 {
00061 template <class T>
00062 class TimeStampedVector: public std::vector<T>
00063 {
00064 public:
00065 typedef typename std::vector<T>::iterator iterator;
00066 void removeBefore(const ros::Time& stamp)
00067 {
00068 for (iterator it = std::vector<T>::begin();
00069 it != std::vector<T>::end();) {
00070 if (((*it)->header.stamp - stamp) < ros::Duration(0.0)) {
00071 it = this->erase(it);
00072 }
00073 else {
00074 ++it;
00075 }
00076 }
00077 }
00078 protected:
00079 private:
00080 };
00081
00082
00083 class ValueStamped
00084 {
00085 public:
00086 typedef boost::shared_ptr<ValueStamped> Ptr;
00087 std_msgs::Header header;
00088 double value;
00089 ValueStamped(const std_msgs::Header& aheader, double avalue):
00090 header(aheader), value(avalue) {
00091 }
00092 ValueStamped() { }
00093 };
00094
00095 class Footcoords
00096 {
00097 public:
00098 typedef message_filters::sync_policies::ExactTime<
00099 geometry_msgs::WrenchStamped,
00100 geometry_msgs::WrenchStamped,
00101 sensor_msgs::JointState,
00102 geometry_msgs::PointStamped> SyncPolicy;
00103 typedef message_filters::sync_policies::ExactTime<
00104 nav_msgs::Odometry,
00105 sensor_msgs::Imu> OdomImuSyncPolicy;
00106
00107 Footcoords();
00108 virtual ~Footcoords();
00109
00110 enum SupportLegStatus
00111 {
00112 LLEG_GROUND, RLEG_GROUND, AIR, BOTH_GROUND
00113 };
00114
00115 enum OdomStatus
00116 {
00117 UNINITIALIZED, INITIALIZING, LLEG_SUPPORT, RLEG_SUPPORT
00118 };
00119
00120 protected:
00121
00122
00123
00124
00125
00126
00127
00128 virtual void filter(const jsk_footstep_controller::SynchronizedForces::ConstPtr& msg);
00129 virtual bool computeMidCoords(const ros::Time& stamp);
00130 virtual bool computeMidCoordsFromSingleLeg(const ros::Time& stamp,
00131 bool use_left_leg);
00132 virtual bool waitForEndEffectorTrasnformation(const ros::Time& stamp);
00133 virtual bool waitForSensorFrameTransformation(const ros::Time& stamp,
00134 const std::string& lsensor_frame,
00135 const std::string& rsensor_frame);
00136 virtual bool updateGroundTF();
00137 virtual void publishTF(const ros::Time& stamp);
00138 virtual void publishState(const std::string& state);
00139 virtual void updateLegDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat);
00140 virtual void publishContactState(const ros::Time& stamp);
00141 virtual double applyLowPassFilter(double current_val, double prev_val) const;
00142 virtual bool allValueLargerThan(TimeStampedVector<ValueStamped::Ptr>& values,
00143 double threshold);
00144 virtual bool allValueSmallerThan(TimeStampedVector<ValueStamped::Ptr>& values,
00145 double threshold);
00146 virtual bool resolveForceTf(const geometry_msgs::WrenchStamped& lfoot,
00147 const geometry_msgs::WrenchStamped& rfoot,
00148 tf::Vector3& lfoot_force, tf::Vector3& rfoot_force);
00149 virtual void periodicTimerCallback(const ros::TimerEvent& event);
00150 virtual void odomInitTriggerCallback(const std_msgs::Empty& trigger);
00151 virtual void odomImuCallback(const nav_msgs::Odometry::ConstPtr& odom_msg,
00152 const sensor_msgs::Imu::ConstPtr& imu_msg);
00153
00154
00155 virtual void synchronizeForces(const geometry_msgs::WrenchStamped::ConstPtr& lfoot,
00156 const geometry_msgs::WrenchStamped::ConstPtr& rfoot,
00157 const sensor_msgs::JointState::ConstPtr& joint_states,
00158 const geometry_msgs::PointStamped::ConstPtr& zmp);
00159 virtual void estimateOdometry();
00160 virtual void estimateOdometryNaive();
00161 virtual void estimateOdometryMainSupportLeg();
00162 virtual void estimateOdometryZMPSupportLeg();
00163 virtual void updateRobotModel(std::map<std::string, double>& joint_angles);
00164 virtual void updateChain(std::map<std::string, double>& joint_angles,
00165 KDL::Chain& chain,
00166 tf::Pose& output_pose);
00167 virtual void estimateVelocity(const ros::Time& stamp, std::map<std::string, double>& joint_angles);
00168 virtual void computeVelicity(double dt,
00169 std::map<std::string, double>& joint_angles,
00170 KDL::Chain& chain,
00171 geometry_msgs::Twist& output);
00172 virtual float getYaw(const Eigen::Affine3d& pose);
00173 virtual void getRollPitch(const Eigen::Affine3d& pose, float& roll, float& pitch);
00174
00175 boost::mutex mutex_;
00176 Eigen::Affine3d odom_pose_;
00177 Eigen::Affine3d odom_init_pose_;
00178 ros::Timer periodic_update_timer_;
00179 ros::Subscriber odom_init_trigger_sub_;
00180
00181 message_filters::Subscriber<nav_msgs::Odometry> odom_sub_;
00182 message_filters::Subscriber<sensor_msgs::Imu> imu_sub_;
00183 boost::shared_ptr<message_filters::Synchronizer<OdomImuSyncPolicy> > odom_imu_sync_;
00184 ros::Subscriber synchronized_forces_sub_;
00185 message_filters::Subscriber<geometry_msgs::WrenchStamped> sub_lfoot_force_;
00186 message_filters::Subscriber<geometry_msgs::WrenchStamped> sub_rfoot_force_;
00187 message_filters::Subscriber<sensor_msgs::JointState> sub_joint_states_;
00188 message_filters::Subscriber<geometry_msgs::PointStamped> sub_zmp_;
00189 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00190 KDL::Chain lfoot_chain_;
00191 KDL::Chain rfoot_chain_;
00192 tf::Pose lfoot_pose_;
00193 tf::Pose rfoot_pose_;
00194 tf::Pose lfoot_to_origin_pose_;
00195 tf::Pose rfoot_to_origin_pose_;
00196 tf::Pose estimated_odom_pose_;
00197 ros::Publisher pub_state_;
00198 ros::Publisher pub_contact_state_;
00199 ros::Publisher pub_low_level_;
00200 ros::Publisher pub_synchronized_forces_;
00201 ros::Publisher pub_debug_lfoot_pos_;
00202 ros::Publisher pub_debug_rfoot_pos_;
00203 ros::Publisher pub_leg_odometory_;
00204 ros::Publisher pub_twist_;
00205 boost::shared_ptr<tf::TransformListener> tf_listener_;
00206 tf::TransformBroadcaster tf_broadcaster_;
00207
00208 std::string zmp_frame_id_;
00209 std::string output_frame_id_;
00210 std::string parent_frame_id_;
00211 std::string midcoords_frame_id_;
00212 SupportLegStatus support_status_;
00213 OdomStatus odom_status_;
00214 Eigen::Vector3f zmp_;
00215 double force_thr_;
00216 bool before_on_the_air_;
00217 std::map<std::string, double> prev_joints_;
00218 bool use_imu_;
00219 bool use_imu_yaw_;
00220 ros::Time last_time_;
00221 std::string lfoot_frame_id_;
00222 std::string rfoot_frame_id_;
00223 std::string lfoot_sensor_frame_;
00224 std::string rfoot_sensor_frame_;
00225 std::string root_frame_id_;
00226 std::string body_on_odom_frame_;
00227 std::string odom_init_frame_id_;
00228 tf::Transform ground_transform_;
00229 tf::Transform midcoords_;
00230 tf::Transform root_link_pose_;
00231 tf::Transform locked_midcoords_to_odom_on_ground_;
00232 boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00233 double prev_lforce_;
00234 double prev_rforce_;
00235 double alpha_;
00236 double sampling_time_;
00237 bool publish_odom_tf_;
00238 private:
00239 };
00240 }
00241 #endif