00001
00026 #include <ros/ros.h>
00027 #include <moveit/robot_state/conversions.h>
00028 #include <stomp_moveit/stomp_planner.h>
00029 #include <class_loader/class_loader.h>
00030 #include <stomp_core/utils.h>
00031 #include <moveit/trajectory_processing/iterative_time_parameterization.h>
00032 #include <stomp_moveit/utils/kinematics.h>
00033 #include <stomp_moveit/utils/polynomial.h>
00034
00035
00036 static const std::string DESCRIPTION = "STOMP";
00037 static const double TIMEOUT_INTERVAL = 0.05;
00038 static int const IK_ATTEMPTS = 10;
00039 static int const IK_TIMEOUT = 0.05;
00040 const static double MAX_START_DISTANCE_THRESH = 0.5;
00041
00049 bool parseConfig(XmlRpc::XmlRpcValue config,const moveit::core::JointModelGroup* group,stomp_core::StompConfiguration& stomp_config)
00050 {
00051 using namespace XmlRpc;
00052
00053 stomp_config.control_cost_weight = 0.0;
00054 stomp_config.initialization_method = 1;
00055 stomp_config.num_timesteps = 40;
00056 stomp_config.delta_t = 1.0;
00057 stomp_config.num_iterations = 50;
00058 stomp_config.num_iterations_after_valid = 0;
00059 stomp_config.max_rollouts = 100;
00060 stomp_config.num_rollouts = 10;
00061 stomp_config.exponentiated_cost_sensitivity = 10.0;
00062
00063
00064 if (config.hasMember("control_cost_weight"))
00065 stomp_config.control_cost_weight = static_cast<double>(config["control_cost_weight"]);
00066
00067 if (config.hasMember("initialization_method"))
00068 stomp_config.initialization_method = static_cast<int>(config["initialization_method"]);
00069
00070 if (config.hasMember("num_timesteps"))
00071 stomp_config.num_timesteps = static_cast<int>(config["num_timesteps"]);
00072
00073 if (config.hasMember("delta_t"))
00074 stomp_config.delta_t = static_cast<double>(config["delta_t"]);
00075
00076 if (config.hasMember("num_iterations"))
00077 stomp_config.num_iterations = static_cast<int>(config["num_iterations"]);
00078
00079 if (config.hasMember("num_iterations_after_valid"))
00080 stomp_config.num_iterations_after_valid = static_cast<int>(config["num_iterations_after_valid"]);
00081
00082 if (config.hasMember("max_rollouts"))
00083 stomp_config.max_rollouts = static_cast<int>(config["max_rollouts"]);
00084
00085 if (config.hasMember("num_rollouts"))
00086 stomp_config.num_rollouts = static_cast<int>(config["num_rollouts"]);
00087
00088 if (config.hasMember("exponentiated_cost_sensitivity"))
00089 stomp_config.exponentiated_cost_sensitivity = static_cast<int>(config["exponentiated_cost_sensitivity"]);
00090
00091
00092 stomp_config.num_dimensions = group->getActiveJointModels().size();
00093 if(stomp_config.num_dimensions == 0)
00094 {
00095 ROS_ERROR("Planning Group %s has no active joints",group->getName().c_str());
00096 return false;
00097 }
00098
00099 return true;
00100 }
00101
00102 namespace stomp_moveit
00103 {
00104
00105 StompPlanner::StompPlanner(const std::string& group,const XmlRpc::XmlRpcValue& config,
00106 const moveit::core::RobotModelConstPtr& model):
00107 PlanningContext(DESCRIPTION,group),
00108 config_(config),
00109 robot_model_(model),
00110 ph_(new ros::NodeHandle("~"))
00111 {
00112 setup();
00113 }
00114
00115 StompPlanner::~StompPlanner()
00116 {
00117 }
00118
00119 void StompPlanner::setup()
00120 {
00121 if(!getPlanningScene())
00122 {
00123 setPlanningScene(planning_scene::PlanningSceneConstPtr(new planning_scene::PlanningScene(robot_model_)));
00124 }
00125
00126
00127 try
00128 {
00129
00130 XmlRpc::XmlRpcValue task_config;
00131 task_config = config_["task"];
00132 task_.reset(new StompOptimizationTask(robot_model_,group_,task_config));
00133
00134 if(!robot_model_->hasJointModelGroup(group_))
00135 {
00136 std::string msg = "Stomp Planning Group '" + group_ + "' was not found";
00137 ROS_ERROR("%s",msg.c_str());
00138 throw std::logic_error(msg);
00139 }
00140
00141
00142 if(!config_.hasMember("optimization") || !parseConfig(config_["optimization" ],robot_model_->getJointModelGroup(group_),stomp_config_))
00143 {
00144 std::string msg = "Stomp 'optimization' parameter for group '" + group_ + "' failed to load";
00145 ROS_ERROR("%s", msg.c_str());
00146 throw std::logic_error(msg);
00147 }
00148
00149 stomp_.reset(new stomp_core::Stomp(stomp_config_,task_));
00150 }
00151 catch(XmlRpc::XmlRpcException& e)
00152 {
00153 throw std::logic_error("Stomp Planner failed to load configuration for group '" + group_+"'; " + e.getMessage());
00154 }
00155
00156 }
00157
00158 bool StompPlanner::solve(planning_interface::MotionPlanResponse &res)
00159 {
00160 ros::WallTime start_time = ros::WallTime::now();
00161 planning_interface::MotionPlanDetailedResponse detailed_res;
00162 bool success = solve(detailed_res);
00163
00164
00165 res.trajectory_ = detailed_res.trajectory_.back();
00166 ros::WallDuration wd = ros::WallTime::now() - start_time;
00167 res.planning_time_ = ros::Duration(wd.sec, wd.nsec).toSec();
00168 res.error_code_ = detailed_res.error_code_;
00169
00170 return success;
00171 }
00172
00173 bool StompPlanner::solve(planning_interface::MotionPlanDetailedResponse &res)
00174 {
00175 using namespace stomp_core;
00176
00177
00178 res.description_.resize(1,"");
00179 res.processing_time_.resize(1);
00180 res.trajectory_.resize(1);
00181 res.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00182
00183 ros::WallTime start_time = ros::WallTime::now();
00184 bool success = false;
00185
00186 trajectory_msgs::JointTrajectory trajectory;
00187 Eigen::MatrixXd parameters;
00188 bool planning_success;
00189
00190
00191 auto config_copy = stomp_config_;
00192
00193
00194 Eigen::MatrixXd initial_parameters;
00195 bool use_seed = getSeedParameters(initial_parameters);
00196
00197
00198
00199 ros::WallDuration allowed_time(request_.allowed_planning_time);
00200 ROS_WARN_COND(TIMEOUT_INTERVAL > request_.allowed_planning_time,
00201 "%s allowed planning time %f is less than the minimum planning time value of %f",
00202 getName().c_str(),request_.allowed_planning_time,TIMEOUT_INTERVAL);
00203 ros::Timer timeout_timer = ph_->createTimer(ros::Duration(TIMEOUT_INTERVAL), [&](const ros::TimerEvent& evnt)
00204 {
00205 if((ros::WallTime::now() - start_time) > allowed_time)
00206 {
00207 ROS_ERROR("%s exceeded allowed time of %f , terminating",getName().c_str(),allowed_time.toSec());
00208 this->terminate();
00209 }
00210
00211 },false);
00212
00213
00214 if (use_seed)
00215 {
00216 ROS_INFO("%s Seeding trajectory from MotionPlanRequest",getName().c_str());
00217
00218
00219 config_copy.num_timesteps = initial_parameters.cols();
00220
00221
00222 if(!task_->setMotionPlanRequest(planning_scene_, request_, config_copy, res.error_code_))
00223 {
00224 res.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00225 return false;
00226 }
00227
00228 stomp_->setConfig(config_copy);
00229 planning_success = stomp_->solve(initial_parameters, parameters);
00230 }
00231 else
00232 {
00233
00234
00235 Eigen::VectorXd start, goal;
00236 if(!getStartAndGoal(start,goal))
00237 {
00238 res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
00239 ROS_ERROR("STOMP failed to get the start and goal positions");
00240 return false;
00241 }
00242
00243
00244 if(!task_->setMotionPlanRequest(planning_scene_,request_, config_copy,res.error_code_))
00245 {
00246 res.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00247 return false;
00248 }
00249
00250 stomp_->setConfig(config_copy);
00251 planning_success = stomp_->solve(start,goal,parameters);
00252 }
00253
00254
00255 timeout_timer.stop();
00256
00257
00258 if(planning_success)
00259 {
00260 if(!parametersToJointTrajectory(parameters,trajectory))
00261 {
00262 res.error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00263 return false;
00264 }
00265
00266
00267 moveit::core::RobotState robot_state(robot_model_);
00268 moveit::core::robotStateMsgToRobotState(request_.start_state,robot_state);
00269 res.trajectory_[0]= robot_trajectory::RobotTrajectoryPtr(new robot_trajectory::RobotTrajectory(
00270 robot_model_,group_));
00271 res.trajectory_.back()->setRobotTrajectoryMsg( robot_state,trajectory);
00272 }
00273 else
00274 {
00275 res.error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00276 return false;
00277 }
00278
00279
00280 if(planning_scene_ && !planning_scene_->isPathValid(*res.trajectory_.back(),group_,true))
00281 {
00282 res.error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00283 success = false;
00284 ROS_ERROR_STREAM("STOMP Trajectory is in collision");
00285 }
00286
00287 ros::WallDuration wd = ros::WallTime::now() - start_time;
00288 res.processing_time_[0] = ros::Duration(wd.sec, wd.nsec).toSec();
00289 ROS_INFO_STREAM("STOMP found a valid path after "<<res.processing_time_[0]<<" seconds");
00290
00291 return true;
00292 }
00293
00294 bool StompPlanner::getSeedParameters(Eigen::MatrixXd& parameters) const
00295 {
00296 using namespace utils::kinematics;
00297 using namespace utils::polynomial;
00298
00299 auto within_tolerance = [&](const Eigen::VectorXd& a, const Eigen::VectorXd& b, double tol) -> bool
00300 {
00301 double dist = (a - b).cwiseAbs().sum();
00302 return dist <= tol;
00303 };
00304
00305 trajectory_msgs::JointTrajectory traj;
00306 if(!extractSeedTrajectory(request_,traj))
00307 {
00308 ROS_DEBUG("%s Found no seed trajectory",getName().c_str());
00309 return false;
00310 }
00311
00312 if(!jointTrajectorytoParameters(traj,parameters))
00313 {
00314 ROS_ERROR("%s Failed to created seed parameters from joint trajectory",getName().c_str());
00315 return false;
00316 }
00317
00318 if(parameters.cols()<= 2)
00319 {
00320 ROS_ERROR("%s Found less than 3 points in seed trajectory",getName().c_str());
00321 return false;
00322 }
00323
00324
00325
00326
00327
00328 moveit::core::RobotState state (robot_model_);
00329 const auto* group = state.getJointModelGroup(group_);
00330 const auto& joint_names = group->getActiveJointModelNames();
00331 const auto& tool_link = group->getLinkModelNames().back();
00332 Eigen::VectorXd start, goal;
00333
00334
00335 if (moveit::core::robotStateMsgToRobotState(request_.start_state, state))
00336 {
00337
00338 start.resize(joint_names.size());
00339 for(auto j = 0u; j < joint_names.size(); j++)
00340 {
00341 start(j) = state.getVariablePosition(joint_names[j]);
00342 }
00343 state.enforceBounds(group);
00344
00345 if(within_tolerance(parameters.leftCols(1),start,MAX_START_DISTANCE_THRESH))
00346 {
00347 parameters.leftCols(1) = start;
00348 }
00349 else
00350 {
00351 ROS_ERROR("%s Start State is in discrepancy with the seed trajectory",getName().c_str());
00352 return false;
00353 }
00354 }
00355 else
00356 {
00357 ROS_ERROR("%s Failed to get start state joints",getName().c_str());
00358 return false;
00359 }
00360
00361
00362 bool found_goal = false;
00363 goal = parameters.rightCols(1);
00364 for(auto& gc : request_.goal_constraints)
00365 {
00366 if(!gc.joint_constraints.empty())
00367 {
00368
00369 for(auto j = 0u; j < gc.joint_constraints.size() ; j++)
00370 {
00371 auto jc = gc.joint_constraints[j];
00372 state.setVariablePosition(jc.joint_name,jc.position);
00373 }
00374
00375
00376 if(!state.satisfiesBounds(group))
00377 {
00378 ROS_ERROR("%s Requested Goal joint pose is out of bounds",getName().c_str());
00379 continue;
00380 }
00381
00382 for(auto j = 0u; j < joint_names.size(); j++)
00383 {
00384 goal(j) = state.getVariablePosition(joint_names[j]);
00385 }
00386
00387 found_goal = true;
00388 break;
00389 }
00390
00391 if(!gc.position_constraints.empty() && !gc.orientation_constraints.empty())
00392 {
00393
00394 const moveit_msgs::PositionConstraint& pos_constraint = gc.position_constraints.front();
00395 const moveit_msgs::OrientationConstraint& orient_constraint = gc.orientation_constraints.front();
00396
00397 KinematicConfig kc;
00398 if(createKinematicConfig(group,pos_constraint,orient_constraint,start,kc) )
00399 {
00400 if(solveIK(boost::make_shared<moveit::core::RobotState>(state),group_,kc,goal))
00401 {
00402 found_goal = true;
00403 break;
00404 }
00405 }
00406 }
00407
00408 }
00409
00410
00411 if(found_goal)
00412 {
00413 if(within_tolerance(parameters.rightCols(1),goal,MAX_START_DISTANCE_THRESH))
00414 {
00415 parameters.rightCols(1) = goal;
00416 }
00417 else
00418 {
00419 ROS_ERROR("%s Goal in seed to far away from Goal requested",getName().c_str());
00420 return false;
00421 }
00422 }
00423 else
00424 {
00425 ROS_ERROR("%s Goal in seed to far away from Goal requested",getName().c_str());
00426 return false;
00427 }
00428
00429 if(!applyPolynomialSmoothing(robot_model_,group_,parameters,5,1e-5))
00430 {
00431 return false;
00432 }
00433
00434 return true;
00435 }
00436
00437 bool StompPlanner::parametersToJointTrajectory(const Eigen::MatrixXd& parameters,
00438 trajectory_msgs::JointTrajectory& trajectory)
00439 {
00440
00441 trajectory.joint_names = robot_model_->getJointModelGroup(group_)->getActiveJointModelNames();
00442 trajectory.points.clear();
00443 trajectory.points.resize(parameters.cols());
00444 std::vector<double> vals(parameters.rows());
00445 std::vector<double> zeros(parameters.rows(),0.0);
00446 for(auto t = 0u; t < parameters.cols() ; t++)
00447 {
00448 Eigen::VectorXd::Map(&vals[0],vals.size()) = parameters.col(t);
00449 trajectory.points[t].positions = vals;
00450 trajectory.points[t].velocities = zeros;
00451 trajectory.points[t].accelerations = zeros;
00452 trajectory.points[t].time_from_start = ros::Duration(0.0);
00453 }
00454
00455 trajectory_processing::IterativeParabolicTimeParameterization time_generator;
00456 robot_trajectory::RobotTrajectory traj(robot_model_,group_);
00457 moveit::core::RobotState robot_state(robot_model_);
00458 moveit::core::robotStateMsgToRobotState(request_.start_state,robot_state);
00459 traj.setRobotTrajectoryMsg(robot_state,trajectory);
00460
00461
00462 moveit_msgs::RobotTrajectory robot_traj_msgs;
00463 if(time_generator.computeTimeStamps(traj,request_.max_velocity_scaling_factor))
00464 {
00465 traj.getRobotTrajectoryMsg(robot_traj_msgs);
00466 trajectory = robot_traj_msgs.joint_trajectory;
00467 }
00468 else
00469 {
00470 ROS_ERROR("%s Failed to generate timing data",getName().c_str());
00471 return false;
00472 }
00473 return true;
00474 }
00475
00476 bool StompPlanner::jointTrajectorytoParameters(const trajectory_msgs::JointTrajectory& traj, Eigen::MatrixXd& parameters) const
00477 {
00478 const auto dof = traj.joint_names.size();
00479 const auto timesteps = traj.points.size();
00480
00481 Eigen::MatrixXd mat (dof, timesteps);
00482
00483 for (size_t step = 0; step < timesteps; ++step)
00484 {
00485 for (size_t joint = 0; joint < dof; ++joint)
00486 {
00487 mat(joint, step) = traj.points[step].positions[joint];
00488 }
00489 }
00490
00491 parameters = mat;
00492 return true;
00493 }
00494
00495 bool StompPlanner::extractSeedTrajectory(const moveit_msgs::MotionPlanRequest& req, trajectory_msgs::JointTrajectory& seed) const
00496 {
00497 if (req.trajectory_constraints.constraints.empty())
00498 return false;
00499
00500 const auto* joint_group = robot_model_->getJointModelGroup(group_);
00501 const auto& names = joint_group->getActiveJointModelNames();
00502 const auto dof = names.size();
00503
00504 const auto& constraints = req.trajectory_constraints.constraints;
00505
00506 for (size_t i = 0; i < constraints.size(); ++i)
00507 {
00508 auto n = constraints[i].joint_constraints.size();
00509 if (n != dof)
00510 {
00511 ROS_WARN("Seed trajectory index %lu does not have %lu constraints (has %lu instead).", i, dof, n);
00512 return false;
00513 }
00514
00515 trajectory_msgs::JointTrajectoryPoint joint_pt;
00516
00517 for (size_t j = 0; j < constraints[i].joint_constraints.size(); ++j)
00518 {
00519 const auto& c = constraints[i].joint_constraints[j];
00520 if (c.joint_name != names[j])
00521 {
00522 ROS_WARN("Seed trajectory (index %lu, joint %lu) joint name '%s' does not match expected name '%s'",
00523 i, j, c.joint_name.c_str(), names[j].c_str());
00524 return false;
00525 }
00526 joint_pt.positions.push_back(c.position);
00527 }
00528
00529 seed.points.push_back(joint_pt);
00530 }
00531
00532 seed.joint_names = names;
00533 return true;
00534 }
00535
00536 moveit_msgs::TrajectoryConstraints StompPlanner::encodeSeedTrajectory(const trajectory_msgs::JointTrajectory &seed)
00537 {
00538 moveit_msgs::TrajectoryConstraints res;
00539
00540 const auto dof = seed.joint_names.size();
00541
00542 for (size_t i = 0; i < seed.points.size(); ++i)
00543 {
00544 moveit_msgs::Constraints c;
00545
00546 if (seed.points[i].positions.size() != dof)
00547 throw std::runtime_error("All trajectory position fields must have same dimensions as joint_names");
00548
00549 for (size_t j = 0; j < dof; ++j)
00550 {
00551 moveit_msgs::JointConstraint jc;
00552 jc.joint_name = seed.joint_names[j];
00553 jc.position = seed.points[i].positions[j];
00554
00555 c.joint_constraints.push_back(jc);
00556 }
00557
00558 res.constraints.push_back(std::move(c));
00559 }
00560
00561 return res;
00562 }
00563
00564 bool StompPlanner::getStartAndGoal(Eigen::VectorXd& start, Eigen::VectorXd& goal)
00565 {
00566 using namespace moveit::core;
00567 using namespace utils::kinematics;
00568
00569 RobotStatePtr state(new RobotState(robot_model_));
00570 const JointModelGroup* joint_group = robot_model_->getJointModelGroup(group_);
00571 std::string tool_link = joint_group->getLinkModelNames().back();
00572 bool found_goal = false;
00573
00574 try
00575 {
00576
00577 if(!robotStateMsgToRobotState(request_.start_state,*state))
00578 {
00579 ROS_ERROR("%s Failed to extract start state from MotionPlanRequest",getName().c_str());
00580 return false;
00581 }
00582
00583
00584 const std::vector<std::string> joint_names= state->getJointModelGroup(group_)->getActiveJointModelNames();
00585 start.resize(joint_names.size());
00586 goal.resize(joint_names.size());
00587
00588 if(!state->satisfiesBounds())
00589 {
00590 ROS_ERROR("%s Start joint pose is out of bounds",getName().c_str());
00591 return false;
00592 }
00593
00594 for(auto j = 0u; j < joint_names.size(); j++)
00595 {
00596 start(j) = state->getVariablePosition(joint_names[j]);
00597 }
00598
00599
00600 if(request_.goal_constraints.empty())
00601 {
00602 ROS_ERROR("%s A goal constraint was not provided",getName().c_str());
00603 return false;
00604 }
00605
00606
00607 for(const auto& gc : request_.goal_constraints)
00608 {
00609 if(!gc.joint_constraints.empty())
00610 {
00611
00612
00613 for(auto j = 0u; j < gc.joint_constraints.size() ; j++)
00614 {
00615 auto jc = gc.joint_constraints[j];
00616 state->setVariablePosition(jc.joint_name,jc.position);
00617 }
00618
00619
00620 if(!state->satisfiesBounds())
00621 {
00622 ROS_ERROR("%s Requested Goal joint pose is out of bounds",getName().c_str());
00623 continue;
00624 }
00625
00626 ROS_DEBUG("%s Found goal from joint constraints",getName().c_str());
00627
00628
00629 for(auto j = 0u; j < joint_names.size(); j++)
00630 {
00631 goal(j) = state->getVariablePosition(joint_names[j]);
00632 }
00633
00634 found_goal = true;
00635 break;
00636
00637 }
00638
00639 if(!gc.position_constraints.empty() && !gc.orientation_constraints.empty())
00640 {
00641
00642 const moveit_msgs::PositionConstraint& pos_constraint = gc.position_constraints.front();
00643 const moveit_msgs::OrientationConstraint& orient_constraint = gc.orientation_constraints.front();
00644
00645 KinematicConfig kc;
00646 if(createKinematicConfig(joint_group,pos_constraint,orient_constraint,start,kc) )
00647 {
00648 if(solveIK(state,group_,kc,goal))
00649 {
00650 ROS_DEBUG("%s Found goal from IK ",getName().c_str());
00651 found_goal = true;
00652 break;
00653 }
00654 }
00655 }
00656
00657 }
00658
00659 ROS_ERROR_COND(!found_goal,"%s was unable to retrieve the goal from the MotionPlanRequest",getName().c_str());
00660
00661 }
00662 catch(moveit::Exception &e)
00663 {
00664 ROS_ERROR("Failure retrieving start or goal state joint values from request %s", e.what());
00665 return false;
00666 }
00667
00668 return found_goal;
00669 }
00670
00671
00672 bool StompPlanner::canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const
00673 {
00674
00675 if(req.group_name != getGroupName())
00676 {
00677 ROS_ERROR("STOMP: Unsupported planning group '%s' requested", req.group_name.c_str());
00678 return false;
00679 }
00680
00681
00682 if (req.goal_constraints.size() != 1)
00683 {
00684 ROS_ERROR("STOMP: Can only handle a single goal region.");
00685 return false;
00686 }
00687
00688
00689 if (req.goal_constraints[0].joint_constraints.size() == 0)
00690 {
00691 ROS_ERROR("STOMP: Can only handle joint space goals.");
00692 return false;
00693 }
00694
00695 return true;
00696 }
00697
00698 bool StompPlanner::terminate()
00699 {
00700 if(stomp_)
00701 {
00702 if(!stomp_->cancel())
00703 {
00704 ROS_ERROR_STREAM("Failed to interrupt Stomp");
00705 return false;
00706 }
00707 }
00708 return true;
00709 }
00710
00711 void StompPlanner::clear()
00712 {
00713 stomp_->clear();
00714 }
00715
00716 bool StompPlanner::getConfigData(ros::NodeHandle &nh, std::map<std::string, XmlRpc::XmlRpcValue> &config, std::string param)
00717 {
00718
00719 XmlRpc::XmlRpcValue stomp_config;
00720 if(!nh.getParam(param, stomp_config))
00721 {
00722 ROS_ERROR("The 'stomp' configuration parameter was not found");
00723 return false;
00724 }
00725
00726
00727 std::string group_name;
00728 try
00729 {
00730 for(XmlRpc::XmlRpcValue::iterator v = stomp_config.begin(); v != stomp_config.end(); v++)
00731 {
00732 group_name = static_cast<std::string>(v->second["group_name"]);
00733 config.insert(std::make_pair(group_name, v->second));
00734 }
00735 return true;
00736 }
00737 catch(XmlRpc::XmlRpcException& e )
00738 {
00739 ROS_ERROR("Unable to parse ROS parameter:\n %s",stomp_config.toXml().c_str());
00740 return false;
00741 }
00742 }
00743
00744
00745 }
00746