00001 #include <vigir_footstep_planner/footstep_planner_node.h>
00002
00003 #include <vigir_footstep_planning_lib/helper.h>
00004 #include <vigir_footstep_planning_lib/visualization/footstep_planning_vis.h>
00005
00006 #include <vigir_footstep_planning_plugins/plugins/state_generator_plugin.h>
00007 #include <vigir_footstep_planning_plugins/plugins/robot_model_plugin.h>
00008 #include <vigir_footstep_planning_plugins/plugins/step_plan_msg_plugin.h>
00009 #include <vigir_footstep_planning_plugins/plugins/collision_check_plugin.h>
00010 #include <vigir_footstep_planning_plugins/plugins/terrain_model_plugin.h>
00011
00012
00013
00014 namespace vigir_footstep_planning
00015 {
00016 FootstepPlannerNode::FootstepPlannerNode(ros::NodeHandle& nh)
00017 {
00018 initPlugins(nh);
00019 init(nh);
00020 }
00021
00022 void FootstepPlannerNode::initPlugins(ros::NodeHandle& nh)
00023 {
00024 vigir_pluginlib::PluginManager::addPluginClassLoader<StateGeneratorPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::StateGeneratorPlugin");
00025 vigir_pluginlib::PluginManager::addPluginClassLoader<StepPlanMsgPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::StepPlanMsgPlugin");
00026 vigir_pluginlib::PluginManager::addPluginClassLoader<ReachabilityPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::ReachabilityPlugin");
00027 vigir_pluginlib::PluginManager::addPluginClassLoader<StepCostEstimatorPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::StepCostEstimatorPlugin");
00028 vigir_pluginlib::PluginManager::addPluginClassLoader<HeuristicPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::HeuristicPlugin");
00029 vigir_pluginlib::PluginManager::addPluginClassLoader<PostProcessPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::PostProcessPlugin");
00030 vigir_pluginlib::PluginManager::addPluginClassLoader<CollisionCheckPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::CollisionCheckPlugin");
00031 vigir_pluginlib::PluginManager::addPluginClassLoader<TerrainModelPlugin>("vigir_footstep_planning_plugins", "vigir_footstep_planning::TerrainModelPlugin");
00032
00034
00035 }
00036
00037 void FootstepPlannerNode::init(ros::NodeHandle& nh)
00038 {
00039 getFootSize(nh, foot_size);
00040
00041
00042 footstep_planner.reset(new FootstepPlanner(nh));
00043
00044
00045 set_active_parameter_set_sub = nh.subscribe<std_msgs::String>("set_active_parameter_set", 1, &FootstepPlannerNode::setParams, this);
00046 step_plan_request_sub = nh.subscribe("step_plan_request", 1, &FootstepPlannerNode::stepPlanRequest, this);
00047 goal_pose_sub = nh.subscribe("/goal_pose", 1, &FootstepPlannerNode::goalPoseCallback, this);
00048
00049
00050 step_plan_pub = nh.advertise<msgs::StepPlan>("step_plan", 1);
00051 step_plan_request_vis_pub = nh.advertise<msgs::StepPlanRequest>("vis/step_plan_request", 1);
00052 step_plan_vis_pub = nh.advertise<msgs::StepPlan>("vis/step_plan", 1);
00053 error_status_pub = nh.advertise<msgs::ErrorStatus>("error_status", 1);
00054 temp_step_plan_pub = nh.advertise<msgs::StepPlan>("temp_step_plan", 1);
00055 feedback_pub = nh.advertise<msgs::PlanningFeedback>("planning_feedback", 1);
00056
00057
00058 generate_feet_pose_client = nh.serviceClient<msgs::GenerateFeetPoseService>("generate_feet_pose");
00059
00060
00061 step_plan_request_srv = nh.advertiseService("step_plan_request", &FootstepPlannerNode::stepPlanRequestService, this);
00062 update_foot_srv = nh.advertiseService("update_foot", &FootstepPlannerNode::updateFootService, this);
00063 update_feet_srv = nh.advertiseService("update_feet", &FootstepPlannerNode::updateFeetService, this);
00064 update_step_plan_srv = nh.advertiseService("update_step_plan", &FootstepPlannerNode::updateStepPlanService, this);
00065
00066
00067 step_plan_request_as = SimpleActionServer<msgs::StepPlanRequestAction>::create(nh, "step_plan_request", true, boost::bind(&FootstepPlannerNode::stepPlanRequestAction, this, boost::ref(step_plan_request_as))
00068 , boost::bind(&FootstepPlannerNode::stepPlanRequestPreempt, this, boost::ref(step_plan_request_as)));
00069 update_foot_as = SimpleActionServer<msgs::UpdateFootAction>::create(nh, "update_foot", true, boost::bind(&FootstepPlannerNode::updateFootAction, this, boost::ref(update_foot_as)));
00070 update_feet_as = SimpleActionServer<msgs::UpdateFeetAction>::create(nh, "update_feet", true, boost::bind(&FootstepPlannerNode::updateFeetAction, this, boost::ref(update_feet_as)));
00071 update_step_plan_as = SimpleActionServer<msgs::UpdateStepPlanAction>::create(nh, "update_step_plan", true, boost::bind(&FootstepPlannerNode::updateStepPlanAction, this, boost::ref(update_step_plan_as)));
00072 }
00073
00074 FootstepPlannerNode::~FootstepPlannerNode()
00075 {
00076 }
00077
00078
00079
00080 void FootstepPlannerNode::planningResultCallback(const msgs::StepPlanRequestService::Response& resp)
00081 {
00082
00083 if (hasError(resp.status))
00084 {
00085 ROS_ERROR("[FootstepPlannerNode] Error while planning steps:\n%s", toString(resp.status).c_str());
00086 return;
00087 }
00088 else if (hasWarning(resp.status))
00089 ROS_WARN("[FootstepPlannerNode] Warning occured:\n%s", toString(resp.status).c_str());
00090
00091
00092 step_plan_pub.publish(resp.step_plan);
00093 temp_step_plan_pub.publish(resp.step_plan);
00094 step_plan_vis_pub.publish(resp.step_plan);
00095 error_status_pub.publish(resp.status);
00096 }
00097
00098 void FootstepPlannerNode::planningResultActionCallback(const msgs::StepPlanRequestService::Response& resp, SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as)
00099 {
00100 boost::recursive_mutex::scoped_lock lock(step_plan_request_as_mutex);
00101
00102
00103 msgs::StepPlanRequestResult result;
00104
00105 result.step_plan = resp.step_plan;
00106 result.status = resp.status;
00107 result.final_eps = resp.final_eps;
00108 result.planning_time = resp.planning_time;
00109
00110 as->finish(result);
00111
00112
00113 if (hasError(resp.status))
00114 {
00115 ROS_ERROR("[FootstepPlannerNode] Error while planning steps:\n%s", toString(resp.status).c_str());
00116 return;
00117 }
00118 else if (hasWarning(resp.status))
00119 ROS_WARN("[FootstepPlannerNode] Warning occured:\n%s", toString(resp.status).c_str());
00120
00121
00122 temp_step_plan_pub.publish(resp.step_plan);
00123 step_plan_vis_pub.publish(resp.step_plan);
00124 error_status_pub.publish(resp.status);
00125 }
00126
00127 void FootstepPlannerNode::planningFeedbackCallback(const msgs::PlanningFeedback& feedback)
00128 {
00129 feedback_pub.publish(feedback);
00130 }
00131
00132 void FootstepPlannerNode::planningFeedbackActionCallback(const msgs::PlanningFeedback& feedback, SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as)
00133 {
00134 planningFeedbackCallback(feedback);
00135
00136 msgs::StepPlanRequestFeedback fb;
00137 fb.feedback = feedback;
00138 as->publishFeedback(fb);
00139 }
00140
00141 void FootstepPlannerNode::planningPreemptionActionCallback(SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as)
00142 {
00143 boost::recursive_mutex::scoped_lock lock(step_plan_request_as_mutex);
00144
00145 if (as->isActive())
00146 as->setPreempted();
00147 }
00148
00149
00150
00151 void FootstepPlannerNode::setParams(const std_msgs::StringConstPtr& params_name)
00152 {
00153 vigir_generic_params::ParameterSet params;
00154
00155 if (!ParameterManager::getParameterSet(params_name->data, params))
00156 ROS_ERROR("[FootstepPlannerNode] setParams: Unknown parameter set '%s'!", params_name->data.c_str());
00157 else if (!footstep_planner->setParams(params))
00158 ROS_ERROR("[FootstepPlannerNode] setParams: Couldn't set parameter set '%s'!", params_name->data.c_str());
00159 else
00160 ParameterManager::setActive(params_name->data);
00161 }
00162
00163 void FootstepPlannerNode::stepPlanRequest(const msgs::StepPlanRequestConstPtr &plan_request)
00164 {
00165 msgs::ErrorStatus status;
00166 msgs::StepPlanRequestService::Request step_plan_request;
00167 step_plan_request.plan_request = *plan_request;
00168
00169
00170 if (step_plan_request.plan_request.start.header.frame_id.empty())
00171 {
00172 status += ErrorStatusWarning(msgs::ErrorStatus::WARN_UNKNOWN, "FootstepPlannerNode", "stepPlanRequest: No valid frame_id was given as start pose. Try to use current robot pose as start.");
00173 status += determineStartFeetPose(step_plan_request.plan_request.start, generate_feet_pose_client, step_plan_request.plan_request.header);
00174
00175 if (hasError(status))
00176 {
00177 ROS_WARN("[FootstepPlannerNode] Can't obtain start feet pose:\n%s", toString(status).c_str());
00178 return;
00179 }
00180 else if (hasWarning(status))
00181 ROS_WARN("[FootstepPlannerNode] Warning occured while obtaining start feet pose:\n%s", toString(status).c_str());
00182 }
00183
00184 step_plan_request_vis_pub.publish(step_plan_request.plan_request);
00185
00186
00187 status = footstep_planner->stepPlanRequest(step_plan_request, boost::bind(&FootstepPlannerNode::planningResultCallback, this, _1)
00188 , boost::bind(&FootstepPlannerNode::planningFeedbackCallback, this, _1));
00189
00190 if (!isOk(status))
00191 ROS_INFO("[FootstepPlannerNode] stepPlanRequest:\n%s", toString(status).c_str());
00192 }
00193
00194 void FootstepPlannerNode::goalPoseCallback(const geometry_msgs::PoseStampedConstPtr& goal_pose)
00195 {
00196
00197 msgs::Feet start_feet_pose;
00198 msgs::ErrorStatus status = determineStartFeetPose(start_feet_pose, generate_feet_pose_client, goal_pose->header);
00199
00200
00201
00202
00203 if (hasError(status))
00204 {
00205 ROS_WARN("[FootstepPlannerNode] Can't obtain start feet pose:\n%s", toString(status).c_str());
00206 return;
00207 }
00208 else if (hasWarning(status))
00209 ROS_WARN("[FootstepPlannerNode] Warning occured while obtaining start feet pose:\n%s", toString(status).c_str());
00210
00211
00212 msgs::Feet goal_feet_pose;
00213 goal_feet_pose.left.pose.position.z = goal_feet_pose.right.pose.position.z = start_feet_pose.left.pose.position.z;
00214 status = determineGoalFeetPose(goal_feet_pose, generate_feet_pose_client, *goal_pose);
00215
00216 if (hasError(status))
00217 {
00218 ROS_WARN("[FootstepPlannerNode] Can't obtain goal feet pose:\n%s", toString(status).c_str());
00219 return;
00220 }
00221 else if (hasWarning(status))
00222 ROS_WARN("[FootstepPlannerNode] Warning occured while obtaining goal feet pose:\n%s", toString(status).c_str());
00223
00224 footstep_planner->updateFeet(goal_feet_pose, msgs::UpdateMode::UPDATE_MODE_MOVE_TO_VALID);
00225
00226
00227 msgs::StepPlanRequestService::Request step_plan_request;
00228 step_plan_request.plan_request.header = goal_pose->header;
00229 step_plan_request.plan_request.start = start_feet_pose;
00230 step_plan_request.plan_request.goal = goal_feet_pose;
00231 step_plan_request.plan_request.start_step_index = 0;
00232 step_plan_request.plan_request.start_foot_selection = msgs::StepPlanRequest::AUTO;
00233 step_plan_request.plan_request.planning_mode = WorldModel::instance().isTerrainModelAvailable() ? static_cast<uint8_t>(msgs::StepPlanRequest::PLANNING_MODE_3D)
00234 : static_cast<uint8_t>(msgs::StepPlanRequest::PLANNING_MODE_2D);
00235 step_plan_request.plan_request.max_planning_time = 0.0;
00236 step_plan_request.plan_request.max_number_steps = 0.0;
00237 step_plan_request.plan_request.max_path_length_ratio = 0.0;
00238 step_plan_request.plan_request.parameter_set_name.data = std::string();
00239
00240
00241 step_plan_request_vis_pub.publish(step_plan_request.plan_request);
00242
00243
00244 status = footstep_planner->stepPlanRequest(step_plan_request, boost::bind(&FootstepPlannerNode::planningResultCallback, this, _1)
00245 , boost::bind(&FootstepPlannerNode::planningFeedbackCallback, this, _1));
00246
00247 if (!isOk(status))
00248 ROS_INFO("[FootstepPlannerNode] goalPoseCallback:\n%s", toString(status).c_str());
00249 }
00250
00251
00252
00253 bool FootstepPlannerNode::stepPlanRequestService(msgs::StepPlanRequestService::Request &req, msgs::StepPlanRequestService::Response &resp)
00254 {
00255
00256 if (req.plan_request.start.header.frame_id.empty())
00257 {
00258 resp.status += ErrorStatusWarning(msgs::ErrorStatus::WARN_UNKNOWN, "FootstepPlannerNode", "stepPlanRequestService: No valid frame_id was given as start pose. Try to use current robot pose as start.");
00259 resp.status += determineStartFeetPose(req.plan_request.start, generate_feet_pose_client, req.plan_request.header);
00260 }
00261
00262 step_plan_request_vis_pub.publish(req.plan_request);
00263
00264
00265 if (!footstep_planner->stepPlanRequestService(req, resp))
00266 resp.status += ErrorStatusError(msgs::ErrorStatus::ERR_UNKNOWN, "FootstepPlannerNode", "stepPlanRequestService: Can't call footstep planner service!");
00267
00268 temp_step_plan_pub.publish(msgs::StepPlanConstPtr(new msgs::StepPlan(resp.step_plan)));
00269 step_plan_vis_pub.publish(msgs::StepPlanConstPtr(new msgs::StepPlan(resp.step_plan)));
00270 error_status_pub.publish(msgs::ErrorStatusConstPtr(new msgs::ErrorStatus(resp.status)));
00271
00272 return true;
00273 }
00274
00275 bool FootstepPlannerNode::updateFootService(msgs::UpdateFootService::Request &req, msgs::UpdateFootService::Response &resp)
00276 {
00277 resp.foot = req.foot;
00278 resp.status = footstep_planner->updateFoot(resp.foot, req.update_mode.mode);
00279 return true;
00280 }
00281
00282 bool FootstepPlannerNode::updateFeetService(msgs::UpdateFeetService::Request &req, msgs::UpdateFeetService::Response &resp)
00283 {
00284 resp.feet = req.feet;
00285 resp.status = footstep_planner->updateFeet(resp.feet, req.update_mode.mode);
00286 return true;
00287 }
00288
00289 bool FootstepPlannerNode::updateStepPlanService(msgs::UpdateStepPlanService::Request &req, msgs::UpdateStepPlanService::Response &resp)
00290 {
00291 resp.step_plan = req.step_plan;
00292 resp.status = footstep_planner->updateStepPlan(resp.step_plan, req.update_mode.mode, req.parameter_set_name.data);
00293 step_plan_vis_pub.publish(msgs::StepPlanConstPtr(new msgs::StepPlan(resp.step_plan)));
00294 return true;
00295 }
00296
00297
00298
00299 void FootstepPlannerNode::stepPlanRequestAction(SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as)
00300 {
00301
00302 footstep_planner->preemptPlanning();
00303
00304 boost::recursive_mutex::scoped_lock lock(step_plan_request_as_mutex);
00305
00306
00307 const msgs::StepPlanRequestGoalConstPtr& goal(as->acceptNewGoal());
00308
00309
00310 if (as->isPreemptRequested())
00311 {
00312 as->setPreempted();
00313 return;
00314 }
00315
00316 msgs::ErrorStatus status;
00317 msgs::StepPlanRequestService::Request step_plan_request;
00318 step_plan_request.plan_request = goal->plan_request;
00319
00320
00321 if (step_plan_request.plan_request.start.header.frame_id.empty())
00322 {
00323 status += ErrorStatusWarning(msgs::ErrorStatus::WARN_UNKNOWN, "FootstepPlannerNode", "stepPlanRequestAction: No valid frame_id was given as start pose. Try to use current robot pose as start.");
00324 status += determineStartFeetPose(step_plan_request.plan_request.start, generate_feet_pose_client, step_plan_request.plan_request.header);
00325 }
00326
00327 step_plan_request_vis_pub.publish(step_plan_request.plan_request);
00328
00329
00330 status = footstep_planner->stepPlanRequest(step_plan_request, boost::bind(&FootstepPlannerNode::planningResultActionCallback, this, _1, boost::ref(as))
00331 , boost::bind(&FootstepPlannerNode::planningFeedbackActionCallback, this, _1, boost::ref(as))
00332 , boost::bind(&FootstepPlannerNode::planningPreemptionActionCallback, this, boost::ref(as)));
00333
00334 if (!isOk(status))
00335 ROS_INFO("[FootstepPlannerNode] stepPlanRequest:\n%s", toString(status).c_str());
00336 }
00337
00338 void FootstepPlannerNode::stepPlanRequestPreempt(SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as)
00339 {
00340 boost::recursive_mutex::scoped_lock lock(step_plan_request_as_mutex);
00341
00342 if (as->isActive())
00343 {
00344 footstep_planner->preemptPlanning();
00345 as->setPreempted();
00346 }
00347 }
00348
00349 void FootstepPlannerNode::updateFootAction(SimpleActionServer<msgs::UpdateFootAction>::Ptr& as)
00350 {
00351 const msgs::UpdateFootGoalConstPtr& goal(as->acceptNewGoal());
00352
00353
00354 if (as->isPreemptRequested())
00355 {
00356 as->setPreempted();
00357 return;
00358 }
00359
00360 msgs::UpdateFootResult result;
00361 result.foot = goal->foot;
00362 result.status = footstep_planner->updateFoot(result.foot, goal->update_mode.mode);
00363
00364 as->finish(result);
00365 }
00366
00367 void FootstepPlannerNode::updateFeetAction(SimpleActionServer<msgs::UpdateFeetAction>::Ptr& as)
00368 {
00369 const msgs::UpdateFeetGoalConstPtr& goal(as->acceptNewGoal());
00370
00371
00372 if (as->isPreemptRequested())
00373 {
00374 as->setPreempted();
00375 return;
00376 }
00377
00378 msgs::UpdateFeetResult result;
00379 result.feet = goal->feet;
00380 result.status = footstep_planner->updateFeet(result.feet, goal->update_mode.mode);
00381
00382 as->finish(result);
00383 }
00384
00385 void FootstepPlannerNode::updateStepPlanAction(SimpleActionServer<msgs::UpdateStepPlanAction>::Ptr& as)
00386 {
00387 const msgs::UpdateStepPlanGoalConstPtr& goal(as->acceptNewGoal());
00388
00389
00390 if (as->isPreemptRequested())
00391 {
00392 as->setPreempted();
00393 return;
00394 }
00395
00396 msgs::UpdateStepPlanResult result;
00397
00398 result.step_plan = goal->step_plan;
00399 result.status = footstep_planner->updateStepPlan(result.step_plan, goal->update_mode.mode, goal->parameter_set_name.data);
00400 step_plan_vis_pub.publish(msgs::StepPlanConstPtr(new msgs::StepPlan(result.step_plan)));
00401
00402 as->finish(result);
00403 }
00404 }
00405
00406 int main(int argc, char** argv)
00407 {
00408 ros::init(argc, argv, "vigir_footstep_planner");
00409
00410 ros::NodeHandle nh;
00411
00412
00413 if (nh.getNamespace().size() <= 1)
00414 nh = ros::NodeHandle("~");
00415
00416
00417 vigir_generic_params::ParameterManager::initialize(nh);
00418 vigir_pluginlib::PluginManager::initialize(nh);
00419
00420
00421 vigir_footstep_planning::FootstepPlannerNode footstep_planner_node(nh);
00422
00423 ros::spin();
00424
00425 return 0;
00426 }