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
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include <iostream>
00038 #include <interactive_markers/tools.h>
00039 #include <jsk_interactive_marker/footstep_marker.h>
00040 #include <jsk_interactive_marker/interactive_marker_utils.h>
00041 #include <jsk_interactive_marker/interactive_marker_helpers.h>
00042 #include <jsk_footstep_msgs/PlanFootstepsGoal.h>
00043 #include <jsk_footstep_msgs/PlanFootstepsResult.h>
00044 #include <std_srvs/Empty.h>
00045 #include <jsk_recognition_msgs/CallSnapIt.h>
00046 #include <Eigen/StdVector>
00047 #include <eigen_conversions/eigen_msg.h>
00048 #include <tf_conversions/tf_eigen.h>
00049 #include <jsk_recognition_utils/geo_util.h>
00050 #include <jsk_recognition_utils/pcl_conversion_util.h>
00051 #include <jsk_recognition_utils/tf_listener_singleton.h>
00052 #include <jsk_interactive_marker/SnapFootPrint.h>
00053 #include <jsk_interactive_marker/SnapFootPrintInput.h>
00054 #include <jsk_interactive_marker/SetHeuristic.h>
00055 #include <jsk_topic_tools/log_utils.h>
00056
00057 FootstepMarker::FootstepMarker():
00058 ac_("footstep_planner", true), ac_exec_("footstep_controller", true),
00059 plan_run_(false), lleg_first_(true) {
00060
00061 tf_listener_.reset(new tf::TransformListener);
00062 ros::NodeHandle pnh("~");
00063 ros::NodeHandle nh;
00064 srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
00065 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00066 boost::bind (&FootstepMarker::configCallback, this, _1, _2);
00067 srv_->setCallback (f);
00068 pnh.param("foot_size_x", foot_size_x_, 0.247);
00069 pnh.param("foot_size_y", foot_size_y_, 0.135);
00070 pnh.param("foot_size_z", foot_size_z_, 0.01);
00071 pnh.param("lfoot_frame_id", lfoot_frame_id_, std::string("lfsensor"));
00072 pnh.param("rfoot_frame_id", rfoot_frame_id_, std::string("rfsensor"));
00073 pnh.param("show_6dof_control", show_6dof_control_, true);
00074
00075
00076 pnh.param("always_planning", always_planning_, true);
00077
00078 project_footprint_pub_ = pnh.advertise<jsk_interactive_marker::SnapFootPrintInput>("project_footprint", 1);
00079
00080
00081 readPoseParam(pnh, "lfoot_offset", lleg_offset_);
00082 readPoseParam(pnh, "rfoot_offset", rleg_offset_);
00083
00084 pnh.param("footstep_margin", footstep_margin_, 0.2);
00085 pnh.param("use_footstep_planner", use_footstep_planner_, true);
00086
00087 pnh.param("use_footstep_controller", use_footstep_controller_, true);
00088 pnh.param("use_initial_footstep_tf", use_initial_footstep_tf_, true);
00089 pnh.param("wait_snapit_server", wait_snapit_server_, false);
00090 bool nowait = true;
00091 pnh.param("no_wait", nowait, true);
00092 pnh.param("frame_id", marker_frame_id_, std::string("/map"));
00093 footstep_pub_ = nh.advertise<jsk_footstep_msgs::FootstepArray>("footstep_from_marker", 1);
00094 snapit_client_ = nh.serviceClient<jsk_recognition_msgs::CallSnapIt>("snapit");
00095 snapped_pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("snapped_pose", 1);
00096 current_pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("current_pose", 1);
00097 estimate_occlusion_client_ = nh.serviceClient<std_srvs::Empty>("require_estimation");
00098 if (!nowait && wait_snapit_server_) {
00099 snapit_client_.waitForExistence();
00100 }
00101
00102 if (pnh.getParam("initial_reference_frame", initial_reference_frame_)) {
00103 use_initial_reference_ = true;
00104 ROS_INFO_STREAM("initial_reference_frame: " << initial_reference_frame_);
00105 }
00106 else {
00107 use_initial_reference_ = false;
00108 ROS_INFO("initial_reference_frame is not specified ");
00109 }
00110
00111 server_.reset( new interactive_markers::InteractiveMarkerServer(ros::this_node::getName()));
00112
00113
00114
00115
00116 menu_handler_.insert( "Look Ground",
00117 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00118 menu_handler_.insert( "Execute the Plan",
00119 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00120 menu_handler_.insert( "Force to replan",
00121 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00122
00123
00124 menu_handler_.insert( "Cancel Walk",
00125 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00126 menu_handler_.insert( "Toggle 6dof marker",
00127 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00128
00129
00130 menu_handler_.insert("Straight Heuristic",
00131 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00132 menu_handler_.insert("Stepcost Heuristic**",
00133 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00134 menu_handler_.insert("LLeg First",
00135 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00136 menu_handler_.insert("RLeg First",
00137 boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
00138 marker_pose_.header.frame_id = marker_frame_id_;
00139 marker_pose_.header.stamp = ros::Time::now();
00140 marker_pose_.pose.orientation.w = 1.0;
00141
00142 resetLegPoses();
00143
00144
00145 lleg_initial_pose_.position.y = footstep_margin_ / 2.0;
00146 lleg_initial_pose_.orientation.w = 1.0;
00147 rleg_initial_pose_.position.y = - footstep_margin_ / 2.0;
00148 rleg_initial_pose_.orientation.w = 1.0;
00149
00150 if (use_initial_reference_) {
00151 while (ros::ok()) {
00152 try {
00153 if (!tf_listener_->waitForTransform(marker_frame_id_, initial_reference_frame_,
00154 ros::Time(0.0), ros::Duration(10.0))) {
00155 ROS_INFO_THROTTLE(1.0,
00156 "waiting for transform %s => %s", marker_frame_id_.c_str(),
00157 initial_reference_frame_.c_str());
00158 continue;
00159 }
00160 ROS_INFO("resolved transform %s => %s", marker_frame_id_.c_str(),
00161 initial_reference_frame_.c_str());
00162 tf::StampedTransform transform;
00163 tf_listener_->lookupTransform(marker_frame_id_, initial_reference_frame_,
00164 ros::Time(0), transform);
00165 marker_pose_.pose.position.x = transform.getOrigin().x();
00166 marker_pose_.pose.position.y = transform.getOrigin().y();
00167 marker_pose_.pose.position.z = transform.getOrigin().z();
00168 marker_pose_.pose.orientation.x = transform.getRotation().x();
00169 marker_pose_.pose.orientation.y = transform.getRotation().y();
00170 marker_pose_.pose.orientation.z = transform.getRotation().z();
00171 marker_pose_.pose.orientation.w = transform.getRotation().w();
00172 break;
00173 }
00174 catch (tf2::TransformException& e) {
00175 ROS_ERROR("Failed to lookup transformation: %s", e.what());
00176 }
00177 }
00178 }
00179
00180 initializeInteractiveMarker();
00181
00182 if (use_footstep_planner_) {
00183 ROS_INFO("waiting planner server...");
00184 ac_.waitForServer();
00185 ROS_INFO("found planner server...");
00186 }
00187 if (use_footstep_controller_) {
00188 ROS_INFO("waiting controller server...");
00189 ac_exec_.waitForServer();
00190 ROS_INFO("found controller server...");
00191 }
00192
00193 move_marker_sub_ = nh.subscribe("move_marker", 1, &FootstepMarker::moveMarkerCB, this);
00194 menu_command_sub_ = nh.subscribe("menu_command", 1, &FootstepMarker::menuCommandCB, this);
00195 exec_sub_ = pnh.subscribe("execute", 1, &FootstepMarker::executeCB, this);
00196 resume_sub_ = pnh.subscribe("resume", 1, &FootstepMarker::resumeCB, this);
00197 plan_if_possible_srv_ = pnh.advertiseService("force_to_replan", &FootstepMarker::forceToReplan, this);
00198 if (use_initial_footstep_tf_) {
00199
00200 while (ros::ok()) {
00201 try {
00202 if (tf_listener_->waitForTransform(lfoot_frame_id_, marker_frame_id_,
00203 ros::Time(0.0), ros::Duration(10.0))
00204 && tf_listener_->waitForTransform(rfoot_frame_id_, marker_frame_id_,
00205 ros::Time(0.0), ros::Duration(10.0))) {
00206 break;
00207 }
00208 ROS_INFO("waiting for transform {%s, %s} => %s", lfoot_frame_id_.c_str(),
00209 rfoot_frame_id_.c_str(), marker_frame_id_.c_str());
00210 }
00211 catch (tf2::TransformException& e) {
00212 ROS_ERROR("Failed to lookup transformation: %s", e.what());
00213 }
00214 }
00215 ROS_INFO("resolved transform {%s, %s} => %s", lfoot_frame_id_.c_str(),
00216 rfoot_frame_id_.c_str(), marker_frame_id_.c_str());
00217 }
00218
00219 projection_sub_ = pnh.subscribe("projected_pose", 1,
00220 &FootstepMarker::projectionCallback, this);
00221
00222 }
00223
00224 void FootstepMarker::configCallback(Config& config, uint32_t level)
00225 {
00226 boost::mutex::scoped_lock lock(plane_mutex_);
00227 use_projection_topic_ = config.use_projection_topic;
00228 use_projection_service_ = config.use_projection_service;
00229 use_plane_snap_ = config.use_plane_snap;
00230 use_2d_ = config.use_2d;
00231 }
00232
00233
00234
00235
00236 double getXMLDoubleValue(XmlRpc::XmlRpcValue val) {
00237 switch(val.getType()) {
00238 case XmlRpc::XmlRpcValue::TypeInt:
00239 return (double)((int)val);
00240 case XmlRpc::XmlRpcValue::TypeDouble:
00241 return (double)val;
00242 default:
00243 return 0;
00244 }
00245 }
00246
00247 void FootstepMarker::readPoseParam(ros::NodeHandle& pnh, const std::string param,
00248 tf::Transform& offset) {
00249 XmlRpc::XmlRpcValue v;
00250 geometry_msgs::Pose pose;
00251 if (pnh.hasParam(param)) {
00252 pnh.param(param, v, v);
00253
00254 if (v.getType() == XmlRpc::XmlRpcValue::TypeArray &&
00255 v.size() == 7) {
00256
00257 pose.position.x = getXMLDoubleValue(v[0]);
00258 pose.position.y = getXMLDoubleValue(v[1]);
00259 pose.position.z = getXMLDoubleValue(v[2]);
00260 pose.orientation.x = getXMLDoubleValue(v[3]);
00261 pose.orientation.y = getXMLDoubleValue(v[4]);
00262 pose.orientation.z = getXMLDoubleValue(v[5]);
00263 pose.orientation.w = getXMLDoubleValue(v[6]);
00264
00265
00266 Eigen::Affine3d e;
00267 tf::poseMsgToEigen(pose, e);
00268 tf::transformEigenToTF(e, offset);
00269 }
00270 else {
00271 ROS_ERROR_STREAM(param << " is malformed, which should be 7 length array");
00272 }
00273 }
00274 else {
00275 ROS_WARN_STREAM("there is no parameter on " << param);
00276 }
00277 }
00278
00279 void FootstepMarker::resetLegPoses() {
00280 lleg_pose_.orientation.x = 0.0;
00281 lleg_pose_.orientation.y = 0.0;
00282 lleg_pose_.orientation.z = 0.0;
00283 lleg_pose_.orientation.w = 1.0;
00284 lleg_pose_.position.x = 0.0;
00285 lleg_pose_.position.y = footstep_margin_ / 2.0;
00286 lleg_pose_.position.z = 0.0;
00287
00288 rleg_pose_.orientation.x = 0.0;
00289 rleg_pose_.orientation.y = 0.0;
00290 rleg_pose_.orientation.z = 0.0;
00291 rleg_pose_.orientation.w = 1.0;
00292 rleg_pose_.position.x = 0.0;
00293 rleg_pose_.position.y = - footstep_margin_ / 2.0;
00294 rleg_pose_.position.z = 0.0;
00295 }
00296
00297 geometry_msgs::Pose FootstepMarker::computeLegTransformation(uint8_t leg) {
00298 geometry_msgs::Pose new_pose;
00299 jsk_recognition_msgs::CallSnapIt srv;
00300 srv.request.request.header.stamp = ros::Time::now();
00301 srv.request.request.header.frame_id = marker_frame_id_;
00302 srv.request.request.target_plane.header.stamp = ros::Time::now();
00303 srv.request.request.target_plane.header.frame_id = marker_frame_id_;
00304 srv.request.request.target_plane.polygon = computePolygon(leg);
00305 if (snapit_client_.call(srv)) {
00306 Eigen::Affine3d A, T, B, B_prime;
00307 tf::poseMsgToEigen(srv.response.transformation, T);
00308 tf::poseMsgToEigen(marker_pose_.pose, A);
00309 if (leg == jsk_footstep_msgs::Footstep::LEFT) {
00310 tf::poseMsgToEigen(lleg_pose_, B);
00311 }
00312 else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
00313 tf::poseMsgToEigen(rleg_pose_, B);
00314 }
00315 B_prime = A.inverse() * T * A * B;
00316 tf::poseEigenToMsg(B_prime, new_pose);
00317 }
00318 else {
00319
00320 ROS_ERROR("failed to call snapit");
00321 }
00322 return new_pose;
00323 }
00324
00325 void FootstepMarker::snapLegs() {
00326 geometry_msgs::Pose l_pose = computeLegTransformation(jsk_footstep_msgs::Footstep::LEFT);
00327 geometry_msgs::Pose r_pose = computeLegTransformation(jsk_footstep_msgs::Footstep::RIGHT);
00328
00329 lleg_pose_ = l_pose;
00330 rleg_pose_ = r_pose;
00331
00332 }
00333
00334 geometry_msgs::Polygon FootstepMarker::computePolygon(uint8_t leg) {
00335 geometry_msgs::Polygon polygon;
00336
00337
00338 std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > points;
00339 points.push_back(Eigen::Vector3d(foot_size_x_ / 2.0, foot_size_y_ / 2.0, 0.0));
00340 points.push_back(Eigen::Vector3d(-foot_size_x_ / 2.0, foot_size_y_ / 2.0, 0.0));
00341 points.push_back(Eigen::Vector3d(-foot_size_x_ / 2.0, -foot_size_y_ / 2.0, 0.0));
00342 points.push_back(Eigen::Vector3d(foot_size_x_ / 2.0, -foot_size_y_ / 2.0, 0.0));
00343
00344 Eigen::Affine3d marker_pose_eigen;
00345 Eigen::Affine3d leg_pose_eigen;
00346 tf::poseMsgToEigen(marker_pose_.pose, marker_pose_eigen);
00347 if (leg == jsk_footstep_msgs::Footstep::LEFT) {
00348 tf::poseMsgToEigen(lleg_pose_, leg_pose_eigen);
00349 }
00350 else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
00351 tf::poseMsgToEigen(rleg_pose_, leg_pose_eigen);
00352 }
00353
00354 for (size_t i = 0; i < points.size(); i++) {
00355 Eigen::Vector3d point = points[i];
00356 Eigen::Vector3d new_point = marker_pose_eigen * leg_pose_eigen * point;
00357 geometry_msgs::Point32 point_msg;
00358 point_msg.x = new_point[0];
00359 point_msg.y = new_point[1];
00360 point_msg.z = new_point[2];
00361 polygon.points.push_back(point_msg);
00362 }
00363
00364 return polygon;
00365 }
00366
00367 void FootstepMarker::executeCB(const std_msgs::Empty::ConstPtr& msg) {
00368 executeFootstep();
00369 }
00370
00371 void FootstepMarker::resumeCB(const std_msgs::Empty::ConstPtr& msg) {
00372 resumeFootstep();
00373 }
00374
00375 void FootstepMarker::menuCommandCB(const std_msgs::UInt8::ConstPtr& msg) {
00376 processMenuFeedback(msg->data);
00377 }
00378
00379 void FootstepMarker::updateInitialFootstep() {
00380
00381 try {
00382 if (!use_initial_footstep_tf_) {
00383 return;
00384 }
00385 tf::StampedTransform lfoot_transform, rfoot_transform;
00386 tf_listener_->lookupTransform(marker_frame_id_, lfoot_frame_id_, ros::Time(0.0), lfoot_transform);
00387 tf_listener_->lookupTransform(marker_frame_id_, rfoot_frame_id_, ros::Time(0.0), rfoot_transform);
00388
00389
00390
00391 Eigen::Affine3d le, re;
00392 tf::transformTFToEigen(lfoot_transform * lleg_offset_, le);
00393 tf::poseEigenToMsg(le, lleg_initial_pose_);
00394 tf::transformTFToEigen(rfoot_transform * rleg_offset_, re);
00395 tf::poseEigenToMsg(re, rleg_initial_pose_);
00396
00397
00398 initializeInteractiveMarker();
00399 }
00400 catch (tf2::TransformException& e) {
00401 ROS_ERROR("Failed to lookup transformation: %s", e.what());
00402 }
00403 }
00404
00405 void FootstepMarker::lookGround()
00406 {
00407 std_srvs::Empty empty;
00408 if (ros::service::call("/lookaround_ground", empty)) {
00409 ROS_INFO("Finished to look ground");
00410 }
00411 else {
00412 ROS_ERROR("Failed to look ground");
00413 }
00414 }
00415
00416 bool FootstepMarker::forceToReplan(std_srvs::Empty::Request& req, std_srvs::Empty::Request& res)
00417 {
00418 planIfPossible();
00419 return true;
00420 }
00421
00422 void FootstepMarker::processMenuFeedback(uint8_t menu_entry_id) {
00423 switch (menu_entry_id) {
00424 case 1: {
00425 lookGround();
00426 break;
00427 }
00428 case 2: {
00429 executeCB(std_msgs::Empty::ConstPtr());
00430 break;
00431 }
00432 case 3: {
00433 planIfPossible();
00434 break;
00435 }
00436 case 4: {
00437 cancelWalk();
00438 break;
00439 }
00440 case 5: {
00441 show_6dof_control_ = !show_6dof_control_;
00442 break;
00443 }
00444 case 6: {
00445 changePlannerHeuristic(":straight-heuristic");
00446 break;
00447 }
00448 case 7: {
00449 changePlannerHeuristic(":stepcost-heuristic**");
00450 break;
00451 }
00452 case 8: {
00453 lleg_first_ = true;
00454 break;
00455 }
00456 case 9: {
00457 lleg_first_ = false;
00458 break;
00459 }
00460
00461 default: {
00462 break;
00463 }
00464 }
00465 }
00466
00467 void FootstepMarker::changePlannerHeuristic(const std::string& heuristic)
00468 {
00469 jsk_interactive_marker::SetHeuristic heuristic_req;
00470 heuristic_req.request.heuristic = heuristic;
00471 if (!ros::service::call("/footstep_planner/set_heuristic", heuristic_req)) {
00472 ROS_ERROR("failed to set heuristic");
00473 }
00474 else {
00475 ROS_INFO("Success to set heuristic: %s", heuristic.c_str());
00476 }
00477 }
00478
00479 void FootstepMarker::cancelWalk()
00480 {
00481 ROS_WARN("canceling walking");
00482 ac_exec_.cancelAllGoals();
00483 ROS_WARN("canceled walking");
00484 }
00485
00486 void FootstepMarker::callEstimateOcclusion()
00487 {
00488 std_srvs::Empty srv;
00489 estimate_occlusion_client_.call(srv);
00490 }
00491
00492 bool FootstepMarker::projectMarkerToPlane()
00493 {
00494 if (use_projection_service_) {
00495 jsk_interactive_marker::SnapFootPrint snap;
00496 snap.request.input_pose = marker_pose_;
00497 snap.request.lleg_pose.orientation.w = 1.0;
00498 snap.request.rleg_pose.orientation.w = 1.0;
00499 snap.request.lleg_pose.position.y = footstep_margin_ / 2.0;
00500 snap.request.rleg_pose.position.y = - footstep_margin_ / 2.0;
00501 if (ros::service::call("project_footprint", snap) && snap.response.success) {
00502
00503 geometry_msgs::PoseStamped resolved_pose;
00504 tf_listener_->transformPose(marker_pose_.header.frame_id,
00505 snap.response.snapped_pose,
00506 resolved_pose);
00507
00508 Eigen::Vector3d projected_point, marker_point;
00509 tf::pointMsgToEigen(marker_pose_.pose.position, marker_point);
00510 tf::pointMsgToEigen(resolved_pose.pose.position, projected_point);
00511 if ((projected_point - marker_point).norm() < 0.3) {
00512 server_->setPose("footstep_marker", resolved_pose.pose);
00513 snapped_pose_pub_.publish(resolved_pose);
00514 current_pose_pub_.publish(resolved_pose);
00515 server_->applyChanges();
00516 marker_pose_.pose = resolved_pose.pose;
00517 return true;
00518 }
00519 else {
00520 return false;
00521 }
00522 }
00523 else {
00524 ROS_WARN("Failed to snap footprint");
00525 return false;
00526 }
00527 }
00528 else if (use_projection_topic_) {
00529 jsk_interactive_marker::SnapFootPrintInput msg;
00530 msg.input_pose = marker_pose_;
00531 msg.lleg_pose.orientation.w = 1.0;
00532 msg.rleg_pose.orientation.w = 1.0;
00533 msg.lleg_pose.position.y = footstep_margin_ / 2.0;
00534 msg.rleg_pose.position.y = - footstep_margin_ / 2.0;
00535 project_footprint_pub_.publish(msg);
00536 return true;
00537 }
00538 }
00539
00540 void FootstepMarker::menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00541 processMenuFeedback(feedback->menu_entry_id);
00542 }
00543
00544 void FootstepMarker::processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00545 boost::mutex::scoped_lock lock(plane_mutex_);
00546
00547 marker_pose_.header = feedback->header;
00548 marker_pose_.pose = feedback->pose;
00549 marker_frame_id_ = feedback->header.frame_id;
00550 bool skip_plan = false;
00551 geometry_msgs::PoseStamped input_pose;
00552 current_pose_pub_.publish(marker_pose_);
00553 try {
00554 if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP) {
00555 if (use_plane_snap_) {
00556 skip_plan = !projectMarkerToPlane();
00557 }
00558 }
00559 if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP && !skip_plan) {
00560 if (always_planning_) planIfPossible();
00561 }
00562 }
00563 catch (tf2::TransformException& e) {
00564 ROS_ERROR("Failed to lookup transformation: %s", e.what());
00565 }
00566 }
00567
00568 void FootstepMarker::resumeFootstep() {
00569 if (!use_footstep_controller_) {
00570 return;
00571 }
00572 actionlib::SimpleClientGoalState state = ac_exec_.getState();
00573 if (!state.isDone()) {
00574 ROS_ERROR("still executing footstep");
00575 return;
00576 }
00577 jsk_footstep_msgs::ExecFootstepsGoal goal;
00578 goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::RESUME;
00579 ac_exec_.sendGoal(goal);
00580 }
00581
00582 void FootstepMarker::projectionCallback(const geometry_msgs::PoseStamped& pose)
00583 {
00584 geometry_msgs::PoseStamped resolved_pose;
00585 tf_listener_->transformPose(marker_pose_.header.frame_id,
00586 pose,
00587 resolved_pose);
00588
00589 Eigen::Vector3d projected_point, marker_point;
00590 tf::pointMsgToEigen(marker_pose_.pose.position, marker_point);
00591 tf::pointMsgToEigen(resolved_pose.pose.position, projected_point);
00592 if ((projected_point - marker_point).norm() < 0.3) {
00593 marker_pose_.pose = resolved_pose.pose;
00594 snapped_pose_pub_.publish(resolved_pose);
00595 current_pose_pub_.publish(resolved_pose);
00596 }
00597 }
00598
00599 void FootstepMarker::executeFootstep() {
00600 if (!use_footstep_controller_) {
00601 return;
00602 }
00603 actionlib::SimpleClientGoalState state = ac_exec_.getState();
00604 if (!state.isDone()) {
00605 ROS_ERROR("still executing footstep");
00606 return;
00607 }
00608 if (!plan_result_) {
00609 ROS_ERROR("no planner result is available");
00610 return;
00611 }
00612
00613
00614 jsk_footstep_msgs::ExecFootstepsGoal goal;
00615 goal.footstep = plan_result_->result;
00616
00617 ROS_INFO("sending goal...");
00618 ac_exec_.sendGoal(goal);
00619
00620
00621 }
00622
00623 void FootstepMarker::planIfPossible() {
00624 boost::mutex::scoped_lock lock(plan_run_mutex_);
00625
00626 if (!use_footstep_planner_) {
00627 return;
00628 }
00629 bool call_planner = !plan_run_;
00630 if (call_planner) {
00631 plan_run_ = true;
00632 jsk_footstep_msgs::PlanFootstepsGoal goal;
00633 jsk_footstep_msgs::FootstepArray goal_footstep;
00634 goal_footstep.header.frame_id = marker_frame_id_;
00635 goal_footstep.header.stamp = ros::Time(0.0);
00636 jsk_footstep_msgs::Footstep goal_left;
00637 goal_left.leg = jsk_footstep_msgs::Footstep::LEFT;
00638 goal_left.pose = getFootstepPose(true);
00639 goal_left.dimensions.x = foot_size_x_;
00640 goal_left.dimensions.y = foot_size_y_;
00641 goal_left.dimensions.z = foot_size_z_;
00642 jsk_footstep_msgs::Footstep goal_right;
00643 goal_right.pose = getFootstepPose(false);
00644 goal_right.leg = jsk_footstep_msgs::Footstep::RIGHT;
00645 goal_right.dimensions.x = foot_size_x_;
00646 goal_right.dimensions.y = foot_size_y_;
00647 goal_right.dimensions.z = foot_size_z_;
00648 goal_footstep.footsteps.push_back(goal_left);
00649 goal_footstep.footsteps.push_back(goal_right);
00650 goal.goal_footstep = goal_footstep;
00651 jsk_footstep_msgs::FootstepArray initial_footstep;
00652 initial_footstep.header.frame_id = marker_frame_id_;
00653 initial_footstep.header.stamp = ros::Time(0.0);
00654
00655 jsk_footstep_msgs::Footstep initial_left;
00656 initial_left.leg = jsk_footstep_msgs::Footstep::LEFT;
00657 initial_left.pose = lleg_initial_pose_;
00658 initial_left.dimensions.x = foot_size_x_;
00659 initial_left.dimensions.y = foot_size_y_;
00660 initial_left.dimensions.z = foot_size_z_;
00661
00662 jsk_footstep_msgs::Footstep initial_right;
00663 initial_right.leg = jsk_footstep_msgs::Footstep::RIGHT;
00664 initial_right.pose = rleg_initial_pose_;
00665 initial_right.dimensions.x = foot_size_x_;
00666 initial_right.dimensions.y = foot_size_y_;
00667 initial_right.dimensions.z = foot_size_z_;
00668 if (lleg_first_) {
00669 initial_footstep.footsteps.push_back(initial_left);
00670 initial_footstep.footsteps.push_back(initial_right);
00671 }
00672 else {
00673 initial_footstep.footsteps.push_back(initial_right);
00674 initial_footstep.footsteps.push_back(initial_left);
00675 }
00676 goal.initial_footstep = initial_footstep;
00677 ac_.sendGoal(goal, boost::bind(&FootstepMarker::planDoneCB, this, _1, _2));
00678 }
00679 }
00680
00681 void FootstepMarker::planDoneCB(const actionlib::SimpleClientGoalState &state,
00682 const PlanResult::ConstPtr &result)
00683 {
00684 boost::mutex::scoped_lock lock(plan_run_mutex_);
00685 ROS_INFO("planDoneCB");
00686 plan_result_ = ac_.getResult();
00687 footstep_pub_.publish(plan_result_->result);
00688 ROS_INFO("planning is finished");
00689 plan_run_ = false;
00690 }
00691
00692 geometry_msgs::Pose FootstepMarker::getFootstepPose(bool leftp) {
00693 tf::Vector3 offset(0, 0, 0);
00694 if (leftp) {
00695 offset[1] = footstep_margin_ / 2.0;
00696 }
00697 else {
00698 offset[1] = - footstep_margin_ / 2.0;
00699 }
00700 tf::Transform marker_origin;
00701 marker_origin.setOrigin(tf::Vector3(marker_pose_.pose.position.x,
00702 marker_pose_.pose.position.y,
00703 marker_pose_.pose.position.z));
00704 marker_origin.setRotation(tf::Quaternion(marker_pose_.pose.orientation.x,
00705 marker_pose_.pose.orientation.y,
00706 marker_pose_.pose.orientation.z,
00707 marker_pose_.pose.orientation.w));
00708 tf::Transform offset_trans;
00709 offset_trans.setRotation(tf::Quaternion(0, 0, 0, 1.0));
00710 offset_trans.setOrigin(offset);
00711
00712 tf::Transform footstep_transform = marker_origin * offset_trans;
00713 geometry_msgs::Pose ret;
00714 ret.position.x = footstep_transform.getOrigin()[0];
00715 ret.position.y = footstep_transform.getOrigin()[1];
00716 ret.position.z = footstep_transform.getOrigin()[2];
00717 ret.orientation.x = footstep_transform.getRotation()[0];
00718 ret.orientation.y = footstep_transform.getRotation()[1];
00719 ret.orientation.z = footstep_transform.getRotation()[2];
00720 ret.orientation.w = footstep_transform.getRotation()[3];
00721 return ret;
00722 }
00723
00724 void FootstepMarker::moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg) {
00725
00726 geometry_msgs::PoseStamped transformed_pose;
00727 tf_listener_->transformPose(marker_frame_id_, *msg, transformed_pose);
00728 geometry_msgs::PoseStamped prev_pose = marker_pose_;
00729 marker_pose_ = transformed_pose;
00730 bool skip_plan = false;
00731 if (use_plane_snap_) {
00732
00733 skip_plan = !projectMarkerToPlane();
00734 if (skip_plan) {
00735 marker_pose_ = prev_pose;
00736 }
00737 }
00738
00739
00740 server_->setPose("footstep_marker", transformed_pose.pose);
00741 server_->applyChanges();
00742 current_pose_pub_.publish(marker_pose_);
00743 if (!skip_plan) {
00744 planIfPossible();
00745 }
00746 }
00747
00748 visualization_msgs::Marker FootstepMarker::makeFootstepMarker(geometry_msgs::Pose pose) {
00749 visualization_msgs::Marker marker;
00750 marker.type = visualization_msgs::Marker::CUBE;
00751 marker.scale.x = foot_size_x_;
00752 marker.scale.y = foot_size_y_;
00753 marker.scale.z = foot_size_z_;
00754 marker.color.a = 1.0;
00755 marker.pose = pose;
00756 return marker;
00757 }
00758
00759 void FootstepMarker::initializeInteractiveMarker() {
00760 visualization_msgs::InteractiveMarker int_marker;
00761 int_marker.header.frame_id = marker_frame_id_;
00762
00763 int_marker.name = "footstep_marker";
00764 int_marker.pose = marker_pose_.pose;
00765 visualization_msgs::Marker left_box_marker = makeFootstepMarker(lleg_pose_);
00766 left_box_marker.color.g = 1.0;
00767
00768 visualization_msgs::InteractiveMarkerControl left_box_control;
00769 left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00770 left_box_control.always_visible = true;
00771 left_box_control.markers.push_back( left_box_marker );
00772
00773 int_marker.controls.push_back( left_box_control );
00774
00775 visualization_msgs::Marker right_box_marker = makeFootstepMarker(rleg_pose_);
00776 right_box_marker.color.r = 1.0;
00777
00778 visualization_msgs::InteractiveMarkerControl right_box_control;
00779 right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00780 right_box_control.always_visible = true;
00781 right_box_control.markers.push_back( right_box_marker );
00782
00783 int_marker.controls.push_back( right_box_control );
00784 if (show_6dof_control_) {
00785 if (use_2d_) {
00786 im_helpers::add3Dof2DControl(int_marker, false);
00787 }
00788 else {
00789 im_helpers::add6DofControl(int_marker, false);
00790 }
00791 }
00792
00793 server_->insert(int_marker,
00794 boost::bind(&FootstepMarker::processFeedbackCB, this, _1));
00795
00796
00797 visualization_msgs::InteractiveMarker initial_lleg_int_marker;
00798 initial_lleg_int_marker.header.frame_id = marker_frame_id_;
00799 initial_lleg_int_marker.name = "left_initial_footstep_marker";
00800 initial_lleg_int_marker.pose.orientation.w = 1.0;
00801 visualization_msgs::Marker initial_left_marker = makeFootstepMarker(lleg_initial_pose_);
00802 initial_left_marker.color.g = 1.0;
00803
00804 visualization_msgs::InteractiveMarkerControl initial_left_box_control;
00805 initial_left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00806 initial_left_box_control.always_visible = true;
00807 initial_left_box_control.markers.push_back(initial_left_marker);
00808
00809 initial_lleg_int_marker.controls.push_back( initial_left_box_control );
00810 server_->insert(initial_lleg_int_marker,
00811 boost::bind(&FootstepMarker::processFeedbackCB, this, _1));
00812
00813 visualization_msgs::InteractiveMarker initial_rleg_int_marker;
00814 initial_rleg_int_marker.header.frame_id = marker_frame_id_;
00815 initial_rleg_int_marker.name = "right_initial_footstep_marker";
00816 initial_rleg_int_marker.pose.orientation.w = 1.0;
00817 visualization_msgs::Marker initial_right_marker = makeFootstepMarker(rleg_initial_pose_);
00818 initial_right_marker.color.r = 1.0;
00819
00820 visualization_msgs::InteractiveMarkerControl initial_right_box_control;
00821 initial_right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00822 initial_right_box_control.always_visible = true;
00823 initial_right_box_control.markers.push_back(initial_right_marker);
00824
00825 initial_rleg_int_marker.controls.push_back( initial_right_box_control );
00826 server_->insert(initial_rleg_int_marker,
00827 boost::bind(&FootstepMarker::processFeedbackCB, this, _1));
00828
00829 menu_handler_.apply( *server_, "footstep_marker");
00830
00831 server_->applyChanges();
00832 }
00833
00834 FootstepMarker::~FootstepMarker() {
00835 }
00836
00837 int main(int argc, char** argv) {
00838 ros::init(argc, argv, "footstep_marker");
00839 FootstepMarker marker;
00840 ros::Rate r(10.0);
00841 while (ros::ok()) {
00842 ros::spinOnce();
00843 marker.updateInitialFootstep();
00844 r.sleep();
00845 }
00846 return 0;
00847 }