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_FOOTSTEP_PLANNING_MSGS_H__
00030 #define VIGIR_FOOTSTEP_PLANNING_MSGS_H__
00031
00032 #include <ros/ros.h>
00033
00034 #include <geometry_msgs/Vector3.h>
00035
00036
00037 #include <vigir_footstep_planning_msgs/EditStep.h>
00038 #include <vigir_footstep_planning_msgs/ErrorStatus.h>
00039 #include <vigir_footstep_planning_msgs/Feet.h>
00040 #include <vigir_footstep_planning_msgs/FeetPoseRequest.h>
00041 #include <vigir_footstep_planning_msgs/FootstepExecutionStatus.h>
00042 #include <vigir_footstep_planning_msgs/Foot.h>
00043 #include <vigir_footstep_planning_msgs/PatternParameters.h>
00044 #include <vigir_footstep_planning_msgs/PatternGeneratorParameters.h>
00045 #include <vigir_footstep_planning_msgs/PlanningFeedback.h>
00046 #include <vigir_footstep_planning_msgs/StepPlanFeedback.h>
00047 #include <vigir_footstep_planning_msgs/StepPlanRequest.h>
00048 #include <vigir_footstep_planning_msgs/StepPlan.h>
00049 #include <vigir_footstep_planning_msgs/Step.h>
00050 #include <vigir_footstep_planning_msgs/UpdateMode.h>
00051
00052
00053 #include <vigir_footstep_planning_msgs/EditStepService.h>
00054 #include <vigir_footstep_planning_msgs/GenerateFeetPoseService.h>
00055 #include <vigir_footstep_planning_msgs/GeneratePatternService.h>
00056 #include <vigir_footstep_planning_msgs/GetStepPlanService.h>
00057 #include <vigir_footstep_planning_msgs/PatternGeneratorParametersService.h>
00058 #include <vigir_footstep_planning_msgs/SetStepPlanService.h>
00059 #include <vigir_footstep_planning_msgs/StepPlanRequestService.h>
00060 #include <vigir_footstep_planning_msgs/StitchStepPlanService.h>
00061 #include <vigir_footstep_planning_msgs/StitchStepPlanService.h>
00062 #include <vigir_footstep_planning_msgs/TransformFeetPosesService.h>
00063 #include <vigir_footstep_planning_msgs/TransformFootPoseService.h>
00064 #include <vigir_footstep_planning_msgs/TransformStepPlanService.h>
00065 #include <vigir_footstep_planning_msgs/StitchStepPlanService.h>
00066 #include <vigir_footstep_planning_msgs/UpdateFeetService.h>
00067 #include <vigir_footstep_planning_msgs/UpdateFootService.h>
00068 #include <vigir_footstep_planning_msgs/UpdateStepPlanService.h>
00069
00070
00071 #include <vigir_footstep_planning_msgs/EditStepAction.h>
00072 #include <vigir_footstep_planning_msgs/ExecuteStepPlanAction.h>
00073 #include <vigir_footstep_planning_msgs/GenerateFeetPoseAction.h>
00074 #include <vigir_footstep_planning_msgs/GeneratePatternAction.h>
00075 #include <vigir_footstep_planning_msgs/GetStepPlanAction.h>
00076 #include <vigir_footstep_planning_msgs/SetStepPlanAction.h>
00077 #include <vigir_footstep_planning_msgs/StepPlanRequestAction.h>
00078 #include <vigir_footstep_planning_msgs/StitchStepPlanAction.h>
00079 #include <vigir_footstep_planning_msgs/UpdateFeetAction.h>
00080 #include <vigir_footstep_planning_msgs/UpdateFootAction.h>
00081 #include <vigir_footstep_planning_msgs/UpdateStepPlanAction.h>
00082
00083
00084
00085 namespace vigir_footstep_planning
00086 {
00087 namespace msgs
00088 {
00089 using namespace vigir_footstep_planning_msgs;
00090 }
00091
00092 msgs::ErrorStatus operator+(const msgs::ErrorStatus& lhs, const msgs::ErrorStatus& rhs);
00093 msgs::ErrorStatus operator+=(msgs::ErrorStatus& lhs, const msgs::ErrorStatus& rhs);
00094
00095 msgs::ErrorStatus isConsistent(const msgs::StepPlan& result);
00096
00097 std::string ErrorStatusCodeToString(unsigned int error);
00098 std::string WarningStatusCodeToString(unsigned int warning);
00099
00100 msgs::ErrorStatus createErrorStatus(const std::string& context, unsigned int error, const std::string& error_msg, unsigned int warning, const std::string& warning_msg, bool output = true, double throttle_rate = 0.0);
00101 msgs::ErrorStatus ErrorStatusError(unsigned int error, const std::string& context, const std::string& error_msg, bool output = true, double throttle_rate = 0.0);
00102 msgs::ErrorStatus ErrorStatusWarning(unsigned int warning, const std::string& context, const std::string& warning_msg, bool output = true, double throttle_rate = 0.0);
00103
00104 bool hasError(const msgs::ErrorStatus& status);
00105 bool hasWarning(const msgs::ErrorStatus& status);
00106 bool isOk(const msgs::ErrorStatus& status);
00107
00108 std::string toString(const msgs::ErrorStatus& error_status);
00109
00110 std::string toString(const msgs::FootstepExecutionStatus& execution_status);
00111
00112 template <typename Tin, typename Tout>
00113 void copyPosition(const Tin &p_in, Tout &p_out)
00114 {
00115 p_out.x = p_in.x;
00116 p_out.y = p_in.y;
00117 p_out.z = p_in.z;
00118 }
00119 }
00120
00121 #endif