$search
00001 #include <sstream> 00002 #include <stdexcept> 00003 #include <boost/bind.hpp> 00004 #include <boost/date_time.hpp> 00005 00006 #include <Eigen/LU> 00007 00008 #include <LinearMath/btMatrix3x3.h> 00009 #include <LinearMath/btQuaternion.h> 00010 00011 #include <ros/ros.h> 00012 00013 #include "halfsteps_pattern_generator.hh" 00014 #include "binary.hh" 00015 #include "yaml.hh" 00016 00017 #include "geometry_msgs/Pose.h" 00018 #include "visualization_msgs/MarkerArray.h" 00019 #include "halfsteps_pattern_generator/GetPath.h" 00020 #include "halfsteps_pattern_generator/Footprint.h" 00021 00022 #include <walk_msgs/conversion.hh> 00023 00024 #include <walk_msgs/abstract-node.hh> 00025 00026 using walk::HomogeneousMatrix3d; 00027 using walk::Posture; 00028 00029 using walk_msgs::convertPoseToHomogeneousMatrix; 00030 using walk_msgs::convertPointToVector3d; 00031 using walk_msgs::convertTrajectoryToPath; 00032 using walk_msgs::convertTrajectoryV3dToPath; 00033 using walk_msgs::convertTrajectoryV2dToPath; 00034 00035 template <typename T> 00036 T getParam (const std::string& param, 00037 const T& defaultValue) 00038 { 00039 T result; 00040 ros::param::param(param, result, defaultValue); 00041 return result; 00042 } 00043 00044 class GeneratorNode : 00045 public walk_msgs::AbstractNode<HalfStepsPatternGenerator, 00046 halfsteps_pattern_generator::Footprint, 00047 halfsteps_pattern_generator::GetPath> 00048 { 00049 public: 00050 explicit GeneratorNode (); 00051 ~GeneratorNode (); 00052 00053 virtual void convertFootprint 00054 (patternGenerator_t::footprints_t& dst, 00055 const std::vector<footprintRosType_t>& src); 00056 00057 virtual void 00058 setupPatternGenerator (serviceRosType_t::Request& req); 00059 }; 00060 00061 GeneratorNode::GeneratorNode () 00062 : walk_msgs::AbstractNode<HalfStepsPatternGenerator, 00063 halfsteps_pattern_generator::Footprint, 00064 halfsteps_pattern_generator::GetPath> 00065 ("", getParam<std::string> ("~world_frame_id", "/world"), 00066 HalfStepsPatternGenerator 00067 (getParam ("~time_before_zmp_shift", 0.95), 00068 getParam ("~time_after_zmp_shift", 1.05), 00069 getParam ("~step", 0.005) 00070 )) 00071 {} 00072 00073 GeneratorNode::~GeneratorNode () 00074 {} 00075 00076 void 00077 GeneratorNode::convertFootprint (patternGenerator_t::footprints_t& dst, 00078 const std::vector<footprintRosType_t>& src) 00079 { 00080 using boost::posix_time::seconds; 00081 using boost::posix_time::milliseconds; 00082 00083 dst.clear(); 00084 std::vector<footprintRosType_t>::const_iterator it = src.begin(); 00085 for (; it != src.end(); ++it) 00086 { 00087 // Check that footprint is valid. 00088 if (it->slideUp < -1.52 || it->slideUp > 0.) 00089 throw std::runtime_error ("invalid up slide"); 00090 if (it->slideDown < -0.76 || it->slideDown > 0.) 00091 throw std::runtime_error ("invalid down slide"); 00092 00093 // Add it to the pattern generator. 00094 HalfStepsPatternGenerator::footprint_t footprint; 00095 footprint.beginTime = (it->footprint.beginTime).toBoost(); 00096 footprint.duration = 00097 seconds(it->footprint.duration.sec) 00098 + milliseconds(it->footprint.duration.nsec * 1000); 00099 footprint.position(0) = it->footprint.x; 00100 footprint.position(1) = it->footprint.y; 00101 footprint.position(2) = it->footprint.theta; 00102 footprint.slideUp = it->slideUp; 00103 footprint.slideDown = it->slideDown; 00104 footprint.horizontalDistance = it->horizontalDistance; 00105 footprint.stepHeight = it->stepHeight; 00106 dst.push_back(footprint); 00107 } 00108 } 00109 00110 void 00111 GeneratorNode::setupPatternGenerator (serviceRosType_t::Request& req) 00112 { 00113 } 00114 00115 00116 int main(int argc, char **argv) 00117 { 00118 try 00119 { 00120 ros::init(argc, argv, "halfsteps_pattern_generator"); 00121 GeneratorNode node; 00122 if (ros::ok()) 00123 node.spin(); 00124 } 00125 catch (std::exception& e) 00126 { 00127 std::cerr << "fatal error: " << e.what() << std::endl; 00128 ROS_ERROR_STREAM("fatal error: " << e.what()); 00129 return 1; 00130 } 00131 catch (...) 00132 { 00133 ROS_ERROR_STREAM("unexpected error"); 00134 return 2; 00135 } 00136 return 0; 00137 } 00138