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 #ifndef VIGIR_PATTERN_GENERATOR_H__
00030 #define VIGIR_PATTERN_GENERATOR_H__
00031
00032 #include <map>
00033
00034 #include <ros/ros.h>
00035 #include <tf/tf.h>
00036
00037 #include <actionlib/client/simple_action_client.h>
00038
00039 #include <geometry_msgs/Pose.h>
00040 #include <geometry_msgs/PoseStamped.h>
00041 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00042
00043 #include <vigir_footstep_planning_lib/helper.h>
00044 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
00045
00046 #include <vigir_pattern_generator/joystick_handler.h>
00047
00048
00049
00050 namespace vigir_footstep_planning
00051 {
00052 class PatternGenerator
00053 {
00054 public:
00055 PatternGenerator(ros::NodeHandle& nh);
00056 virtual ~PatternGenerator();
00057
00058 void reset();
00059 void setParams(const msgs::PatternGeneratorParameters& params);
00060 void setEnabled(bool enabled);
00061 bool isEnabled() const;
00062 bool isSimulationMode() const;
00063
00064 bool hasSteps() const;
00065 bool hasNewSteps() const;
00066 void getCompleteStepPlan(msgs::StepPlan& step_plan) const;
00067 void getNewestStepPlan(msgs::StepPlan& step_plan) const;
00068 void clearStepPlan();
00069
00070 bool setNextStartStepIndex(int step_index);
00071 int getNextStartStepIndex() const;
00072
00073 void update(const ros::TimerEvent& timer);
00074 void updateLastPerformedStepIndex(int last_performed_step_index);
00075 void updateFirstChangeableStepIndex(int first_changeable_step_index);
00076
00077
00078 msgs::ErrorStatus generatePattern(const msgs::StepPlanRequest& step_plan_request, msgs::StepPlan& step_plan);
00079
00080
00081 typedef boost::shared_ptr<PatternGenerator> Ptr;
00082 typedef boost::shared_ptr<PatternGenerator> ConstPtr;
00083
00084 private:
00085 void updateFeetStartPose(uint8_t foot_index, const geometry_msgs::Pose& pose);
00086 void updateFeetStartPose(const msgs::Foot& foot);
00087 void updateFeetStartPose(const msgs::Feet& feet);
00088 void updateFeetStartPose(const msgs::Step& step);
00089 bool updateFeetStartPoseByStepMap(const std::map<unsigned int, msgs::Step>& map, unsigned int step_index);
00090
00091 void updateFootstepMap(std::map<unsigned int, msgs::Step>& map, const std::vector<msgs::Step>& vec) const;
00092 void mapToVectorIndexed(const std::map<unsigned int, msgs::Step>& map, std::vector<msgs::Step>& vec, unsigned int start_index, unsigned int end_index) const;
00093
00094 void generateSteps(unsigned int n, bool close_step = false);
00095
00096
00097 ros::ServiceClient generate_feet_pose_client;
00098 ros::ServiceClient step_plan_request_client;
00099 ros::ServiceClient stitch_step_plan_client;
00100
00101
00102 boost::shared_ptr<actionlib::SimpleActionClient<msgs::ExecuteStepPlanAction> > execute_step_plan_ac;
00103
00104
00105 JoystickHandler::Ptr joystick_handler;
00106 geometry_msgs::Pose joy_d_step;
00107
00108
00109 std::string world_frame_id;
00110 unsigned int number_of_steps_needed;
00111 msgs::PatternGeneratorParameters params;
00112
00113
00114 int last_performed_step_index;
00115 int first_changeable_step_index;
00116 int next_step_index_needed;
00117
00118
00119 msgs::Feet::Ptr start_feet_pose;
00120 unsigned int foot_start_step_index_left;
00121 unsigned int foot_start_step_index_right;
00122 mutable bool has_new_steps;
00123
00124
00125 msgs::StepPlan complete_step_plan;
00126 msgs::StepPlan newest_step_plan;
00127 std::map<unsigned int, msgs::Step> step_map;
00128 };
00129 }
00130
00131 #endif