29 #ifndef VIGIR_FOOTSTEP_PLANNING_MSGS_H__ 30 #define VIGIR_FOOTSTEP_PLANNING_MSGS_H__ 34 #include <geometry_msgs/Vector3.h> 37 #include <vigir_footstep_planning_msgs/EditStep.h> 38 #include <vigir_footstep_planning_msgs/ErrorStatus.h> 39 #include <vigir_footstep_planning_msgs/Feet.h> 40 #include <vigir_footstep_planning_msgs/FeetPoseRequest.h> 41 #include <vigir_footstep_planning_msgs/FootstepExecutionStatus.h> 42 #include <vigir_footstep_planning_msgs/Foot.h> 43 #include <vigir_footstep_planning_msgs/PatternParameters.h> 44 #include <vigir_footstep_planning_msgs/PatternGeneratorParameters.h> 45 #include <vigir_footstep_planning_msgs/PlanningFeedback.h> 46 #include <vigir_footstep_planning_msgs/StepPlanFeedback.h> 47 #include <vigir_footstep_planning_msgs/StepPlanRequest.h> 48 #include <vigir_footstep_planning_msgs/StepPlan.h> 49 #include <vigir_footstep_planning_msgs/Step.h> 50 #include <vigir_footstep_planning_msgs/UpdateMode.h> 53 #include <vigir_footstep_planning_msgs/EditStepService.h> 54 #include <vigir_footstep_planning_msgs/GenerateFeetPoseService.h> 55 #include <vigir_footstep_planning_msgs/GetStepPlanService.h> 56 #include <vigir_footstep_planning_msgs/PatternGeneratorParametersService.h> 57 #include <vigir_footstep_planning_msgs/SetStepPlanService.h> 58 #include <vigir_footstep_planning_msgs/StepPlanRequestService.h> 59 #include <vigir_footstep_planning_msgs/StitchStepPlanService.h> 60 #include <vigir_footstep_planning_msgs/StitchStepPlanService.h> 61 #include <vigir_footstep_planning_msgs/TransformFeetPosesService.h> 62 #include <vigir_footstep_planning_msgs/TransformFootPoseService.h> 63 #include <vigir_footstep_planning_msgs/TransformStepPlanService.h> 64 #include <vigir_footstep_planning_msgs/StitchStepPlanService.h> 65 #include <vigir_footstep_planning_msgs/UpdateFeetService.h> 66 #include <vigir_footstep_planning_msgs/UpdateFootService.h> 67 #include <vigir_footstep_planning_msgs/UpdateStepPlanService.h> 70 #include <vigir_footstep_planning_msgs/EditStepAction.h> 71 #include <vigir_footstep_planning_msgs/ExecuteStepPlanAction.h> 72 #include <vigir_footstep_planning_msgs/GenerateFeetPoseAction.h> 73 #include <vigir_footstep_planning_msgs/GetStepPlanAction.h> 74 #include <vigir_footstep_planning_msgs/SetStepPlanAction.h> 75 #include <vigir_footstep_planning_msgs/StepPlanRequestAction.h> 76 #include <vigir_footstep_planning_msgs/StitchStepPlanAction.h> 77 #include <vigir_footstep_planning_msgs/UpdateFeetAction.h> 78 #include <vigir_footstep_planning_msgs/UpdateFootAction.h> 79 #include <vigir_footstep_planning_msgs/UpdateStepPlanAction.h> 90 msgs::ErrorStatus
operator+(
const msgs::ErrorStatus& lhs,
const msgs::ErrorStatus& rhs);
91 msgs::ErrorStatus
operator+=(msgs::ErrorStatus& lhs,
const msgs::ErrorStatus& rhs);
93 msgs::ErrorStatus
isConsistent(
const msgs::StepPlan& result);
98 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);
99 msgs::ErrorStatus
ErrorStatusError(
unsigned int error,
const std::string& context,
const std::string& error_msg,
bool output =
true,
double throttle_rate = 0.0);
100 msgs::ErrorStatus
ErrorStatusWarning(
unsigned int warning,
const std::string& context,
const std::string& warning_msg,
bool output =
true,
double throttle_rate = 0.0);
102 bool hasError(
const msgs::ErrorStatus& status);
103 bool hasWarning(
const msgs::ErrorStatus& status);
104 bool isOk(
const msgs::ErrorStatus& status);
106 std::string
toString(
const msgs::ErrorStatus& error_status);
108 std::string
toString(
const msgs::FootstepExecutionStatus& execution_status);
110 template <
typename Tin,
typename Tout>