37 #include <jsk_topic_tools/log_utils.h>
40 #include <boost/format.hpp>
41 #include <pcl/common/eigen.h>
44 #include <jsk_topic_tools/rosparam_utils.h>
45 #include <jsk_interactive_marker/SnapFootPrint.h>
46 #include <jsk_footstep_planner/CollisionBoundingBoxInfo.h>
47 #include <dynamic_reconfigure/Reconfigure.h>
49 #define printAffine(af) { \
50 geometry_msgs::Pose __geom_pose;\
51 tf::poseEigenToMsg(af, __geom_pose);\
52 std::cerr << __geom_pose.position.x << ", ";\
53 std::cerr << __geom_pose.position.y << ", ";\
54 std::cerr << __geom_pose.position.z << " / ";\
55 std::cerr << __geom_pose.orientation.w << ", ";\
56 std::cerr << __geom_pose.orientation.x << ", ";\
57 std::cerr << __geom_pose.orientation.y << ", ";\
58 std::cerr << __geom_pose.orientation.z << std::endl; }
74 visualization_msgs::InteractiveMarkerControl control;
77 control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
79 control.orientation.w = 1;
80 control.orientation.x = 1;
81 control.orientation.y = 0;
82 control.orientation.z = 0;
85 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
86 msg.controls.push_back(control);
88 control.orientation.w = 1;
89 control.orientation.x = 0;
90 control.orientation.y = 1;
91 control.orientation.z = 0;
92 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
93 msg.controls.push_back(control);
97 control.orientation.w = 1;
98 control.orientation.x = 0;
99 control.orientation.y = 0;
100 control.orientation.z = 1;
103 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
104 msg.controls.push_back(control);
109 const FootstepTrans& second,
const std::string& second_name):
110 first_(first), first_name_(first_name),
111 second_(second), second_name_(second_name)
137 pnh_(
"~"), ac_planner_(
"footstep_planner", true), ac_exec_(
"footstep_controller", true),
138 pub_marker_array_(pnh_,
"marker_array"),
139 is_2d_mode_(true), is_cube_mode_(false), command_mode_(
SINGLE), have_last_step_(false),
140 planning_state_(NOT_STARTED)
142 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (
pnh_);
143 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
145 srv_->setCallback (
f);
155 std::vector<double> lleg_footstep_offset, rleg_footstep_offset;
156 if (jsk_topic_tools::readVectorParameter(
pnh_,
"lleg_footstep_offset", lleg_footstep_offset)) {
161 if (jsk_topic_tools::readVectorParameter(
pnh_,
"rleg_footstep_offset", rleg_footstep_offset)) {
169 ros::ServiceClient bbox_client = nh.
serviceClient<jsk_footstep_planner::CollisionBoundingBoxInfo>(
"footstep_planner/collision_bounding_box_info",
false);
172 jsk_footstep_planner::CollisionBoundingBoxInfo bbox_info;
173 if (bbox_client.
call(bbox_info)) {
224 if (leg == jsk_footstep_msgs::Footstep::LLEG) {
226 footpose =
pose * ltrans;
227 }
else if (leg == jsk_footstep_msgs::Footstep::RLEG) {
229 footpose =
pose * rtrans;
231 ROS_ERROR (
"makeFootstepMarker not implemented leg (%d)", leg);
233 visualization_msgs::Marker
marker;
235 marker.type = visualization_msgs::Marker::CUBE;
242 marker.type = visualization_msgs::Marker::LINE_STRIP;
252 geometry_msgs::Point ros_a, ros_b, ros_c, ros_d;
253 ros_a.x =
a[0]; ros_a.y =
a[1]; ros_a.z =
a[2];
254 ros_b.x =
b[0]; ros_b.y =
b[1]; ros_b.z =
b[2];
255 ros_c.x =
c[0]; ros_c.y =
c[1]; ros_c.z =
c[2];
256 ros_d.x =
d[0]; ros_d.y =
d[1]; ros_d.z =
d[2];
257 marker.points.push_back(ros_a);
258 marker.points.push_back(ros_b);
259 marker.points.push_back(ros_c);
260 marker.points.push_back(ros_d);
261 marker.points.push_back(ros_a);
268 visualization_msgs::InteractiveMarker& int_marker)
273 jsk_footstep_msgs::Footstep::LLEG);
274 left_box_marker.color.g = 1.0;
276 jsk_footstep_msgs::Footstep::RLEG);
277 right_box_marker.color.r = 1.0;
278 visualization_msgs::InteractiveMarkerControl left_box_control;
279 left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
280 left_box_control.always_visible =
true;
281 left_box_control.markers.push_back(left_box_marker);
282 int_marker.controls.push_back(left_box_control);
283 visualization_msgs::InteractiveMarkerControl right_box_control;
284 right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
285 right_box_control.always_visible =
true;
286 right_box_control.markers.push_back(right_box_marker);
287 int_marker.controls.push_back(right_box_control);
288 int_marker.name =
"initial_footstep_marker";
289 int_marker.description =
"Initial Footsteps";
293 visualization_msgs::InteractiveMarker& int_goal_marker)
295 int_goal_marker.name =
"movable_footstep_marker";
296 int_goal_marker.description =
"Goal Footsteps";
301 left_box_marker.color.g = 1.0;
303 right_box_marker.color.r = 1.0;
304 visualization_msgs::InteractiveMarkerControl left_box_control;
305 left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
306 left_box_control.always_visible =
true;
307 left_box_control.markers.push_back(left_box_marker);
308 int_goal_marker.controls.push_back(left_box_control);
309 visualization_msgs::InteractiveMarkerControl right_box_control;
310 right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
311 right_box_control.always_visible =
true;
312 right_box_control.markers.push_back(right_box_marker);
313 int_goal_marker.controls.push_back(right_box_control);
337 visualization_msgs::InteractiveMarker int_marker;
344 visualization_msgs::InteractiveMarker int_goal_marker;
356 server_->insert(int_goal_marker,
422 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
425 if (
state.isDone()) {
432 const ExecResult::ConstPtr &result)
439 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
450 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
455 jsk_footstep_msgs::ExecFootstepsGoal goal;
463 goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::NEW_TARGET;
466 ROS_INFO(
"Execute footsteps single");
470 goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::RESUME;
472 goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::NEW_TARGET;
477 if(
plan_result_.footsteps[
size-1].leg == jsk_footstep_msgs::Footstep::LEFT) {
486 if (goal.strategy == jsk_footstep_msgs::ExecFootstepsGoal::NEW_TARGET) {
487 ROS_INFO(
"Execute footsteps continuous(new)");
489 ROS_INFO(
"Execute footsteps continuous(added)");
495 ROS_FATAL(
"actionlib server is not connected");
501 ROS_FATAL(
"cannot execute footstep because planning state is ON_GOING");
504 ROS_FATAL(
"cannot execute footstep because planning state is NOT_STARTED");
509 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
523 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
537 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
552 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
567 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
581 dynamic_reconfigure::Reconfigure rconf;
582 dynamic_reconfigure::StrParameter spara;
583 spara.name =
"heuristic";
584 spara.value =
"path_cost";
585 rconf.request.config.strs.push_back(spara);
588 ROS_ERROR(
"Dynamic reconfigure: set parameters failed");
596 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
610 dynamic_reconfigure::Reconfigure rconf;
611 dynamic_reconfigure::StrParameter spara;
612 spara.name =
"heuristic";
613 spara.value =
"path_cost";
614 rconf.request.config.strs.push_back(spara);
617 ROS_ERROR(
"Dynamic reconfigure: set parameters failed");
625 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
641 dynamic_reconfigure::Reconfigure rconf;
642 dynamic_reconfigure::StrParameter spara;
643 spara.name =
"heuristic";
644 spara.value =
"follow_path";
645 rconf.request.config.strs.push_back(spara);
648 ROS_ERROR(
"Dynamic reconfigure: set parameters failed");
656 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
670 const std_msgs::Header& header,
673 jsk_footstep_msgs::FootstepArray footstep_array;
674 footstep_array.header =
header;
677 lleg.leg = jsk_footstep_msgs::Footstep::LEFT;
678 rleg.leg = jsk_footstep_msgs::Footstep::RIGHT;
686 footstep_array.footsteps.push_back(lleg);
687 footstep_array.footsteps.push_back(rleg);
690 footstep_array.footsteps.push_back(rleg);
691 footstep_array.footsteps.push_back(lleg);
693 return footstep_array;
702 jsk_interactive_marker::SnapFootPrint srv_arg;
706 srv_arg.request.input_pose.header =
header;
713 if (
ros::service::call(
"footstep_planner/project_footprint_with_local_search", srv_arg)) {
714 if (srv_arg.response.success) {
725 jsk_footstep_msgs::PlanFootstepsGoal goal;
728 goal.initial_footstep
736 const PlanResult::ConstPtr &result)
762 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
764 if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP) {
777 else if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN) {
780 else if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE) {
800 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
802 visualization_msgs::Marker
marker;
804 marker.type = visualization_msgs::Marker::ARROW;
815 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
817 visualization_msgs::Marker
marker;
819 marker.type = visualization_msgs::Marker::LINE_LIST;
822 marker.color.r = 24 / 255.0;
823 marker.color.g = 240 / 255.0;
829 FootstepVec normalized_direction = direction.normalized();
831 FootstepVec rotate_axis = original_x_direction.cross(normalized_direction).normalized();
832 double pose_theta = acos(original_x_direction.dot(normalized_direction));
834 if (pose_theta == 0.0) {
841 double distance = (
origin.inverse() * posef).translation().norm();
844 const size_t resolustion = 100;
845 const double max_z = 1.0;
846 const double z_ratio = max_z / 2.0 /
r;
847 for (
size_t i = 0;
i < resolustion - 1;
i++) {
849 double next_theta = 2.0 *
M_PI / resolustion * (
i + 1);
852 geometry_msgs::Point ros_p;
856 geometry_msgs::Point ros_q;
861 marker.points.push_back(ros_p);
863 marker.points.push_back(ros_q);
869 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
871 visualization_msgs::Marker
marker;
873 marker.type = visualization_msgs::Marker::LINE_STRIP;
876 marker.color.r = 24 / 255.0;
877 marker.color.g = 240 / 255.0;
882 const double r = 0.5;
886 geometry_msgs::Point ros_p;
890 marker.points.push_back(ros_p);
897 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
899 visualization_msgs::Marker
marker;
900 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
901 Eigen::Affine3f posef;
903 Eigen::Affine3f text_pose = posef * Eigen::Translation3f(-0.1, 0, 0.1);
904 Eigen::Affine3f midcoords;
906 Eigen::Affine3f
transform = midcoords * posef;
908 float roll, pitch, yaw;
909 pcl::getEulerAngles(
transform, roll, pitch, yaw);
911 marker.text = (boost::format(
"pos[m] = (%.2f, %.2f, %.2f)\nrot[deg] = (%.2f, %.2f, %.2f)\n%.2f [m]\n%.0f [deg]")
927 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
929 visualization_msgs::Marker
marker;
931 marker.type = visualization_msgs::Marker::CUBE;
943 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
945 visualization_msgs::Marker
marker;
947 marker.type = visualization_msgs::Marker::CUBE;
961 const std_msgs::Header& header,
const geometry_msgs::Pose& pose)
963 visualization_msgs::Marker
marker;
968 marker.type = visualization_msgs::Marker::LINE_LIST;
970 std_msgs::ColorRGBA col;
980 geometry_msgs::Point ros_p;
984 geometry_msgs::Point ros_q;
988 marker.colors.push_back(col);
989 marker.points.push_back(ros_p);
990 marker.colors.push_back(col);
991 marker.points.push_back(ros_q);
995 geometry_msgs::Point ros_p;
999 geometry_msgs::Point ros_q;
1000 ros_q.x =
pose.position.x;
1001 ros_q.y =
pose.position.y;
1002 ros_q.z =
pose.position.z;
1006 marker.colors.push_back(col);
1007 marker.points.push_back(ros_p);
1008 marker.colors.push_back(col);
1009 marker.points.push_back(ros_q);
1027 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
1049 ROS_WARN(
"tf error, retry: %s", e.what());
1058 geometry_msgs::TransformStamped lleg_transform
1060 geometry_msgs::TransformStamped rleg_transform
1084 const geometry_msgs::PoseStamped::ConstPtr& msg)
1086 ROS_DEBUG(
"posestamped command is received");
1087 ROS_INFO(
"posestamped command is received");
1088 geometry_msgs::PoseStamped tmp_pose_stamped;
1103 tmp_pose_stamped.header.stamp =
msg->header.stamp;
1106 ROS_ERROR(
"posestamped command transformation failed %s",
ex.what());
1110 tmp_pose_stamped = *
msg;
1112 server_->setPose(
"movable_footstep_marker", tmp_pose_stamped.pose, tmp_pose_stamped.header);
1115 visualization_msgs::InteractiveMarkerFeedback dummy_feedback;
1116 dummy_feedback.header = tmp_pose_stamped.header;
1117 dummy_feedback.pose = tmp_pose_stamped.pose;
1118 dummy_feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
1119 const visualization_msgs::InteractiveMarkerFeedbackConstPtr dummy_feedback_ptr
1120 = boost::make_shared<const visualization_msgs::InteractiveMarkerFeedback>(dummy_feedback);
1125 std_srvs::Empty::Request& req,
1126 std_srvs::Empty::Response& res)
1129 visualization_msgs::InteractiveMarkerFeedback dummy_feedback;
1130 const visualization_msgs::InteractiveMarkerFeedbackConstPtr dummy_feedback_ptr
1131 = boost::make_shared<const visualization_msgs::InteractiveMarkerFeedback>(dummy_feedback);
1137 std_srvs::Empty::Request& req,
1138 std_srvs::Empty::Response& res)
1140 visualization_msgs::InteractiveMarkerFeedback dummy_feedback;
1141 const visualization_msgs::InteractiveMarkerFeedbackConstPtr dummy_feedback_ptr
1142 = boost::make_shared<const visualization_msgs::InteractiveMarkerFeedback>(dummy_feedback);
1167 std_srvs::Empty::Request& req,
1168 std_srvs::Empty::Response& res)
1171 visualization_msgs::InteractiveMarkerFeedback dummy_feedback;
1172 const visualization_msgs::InteractiveMarkerFeedbackConstPtr dummy_feedback_ptr
1173 = boost::make_shared<const visualization_msgs::InteractiveMarkerFeedback>(dummy_feedback);
1185 std_srvs::Empty::Request& req,
1186 std_srvs::Empty::Response& res)
1190 if(!
state.isDone()) {
1197 std_srvs::Empty::Request& req,
1198 std_srvs::Empty::Response& res)
1202 if(!
state.isDone()) {
1209 jsk_interactive_marker::GetTransformableMarkerPose::Request& req,
1210 jsk_interactive_marker::GetTransformableMarkerPose::Response& res)
1213 std::string target_name =
req.target_name;
1214 visualization_msgs::InteractiveMarker int_marker;
1215 if (
server_->get(target_name, int_marker)) {
1216 geometry_msgs::PoseStamped ret_pose_stamped;
1217 ret_pose_stamped.header = int_marker.header;
1218 ret_pose_stamped.pose = int_marker.pose;
1219 res.pose_stamped = ret_pose_stamped;
1222 ROS_WARN(
"There is no marker named %s", target_name.c_str());
1228 jsk_interactive_marker::SetPose::Request& req,
1229 jsk_interactive_marker::SetPose::Response& res)
1235 visualization_msgs::InteractiveMarkerFeedback dummy_feedback;
1236 dummy_feedback.header =
req.pose.header;
1237 dummy_feedback.pose =
req.pose.pose;
1238 const visualization_msgs::InteractiveMarkerFeedbackConstPtr dummy_feedback_ptr
1239 = boost::make_shared<const visualization_msgs::InteractiveMarkerFeedback>(dummy_feedback);
1246 std_msgs::ColorRGBA color;
1247 color.r = 0.3568627450980392;
1248 color.g = 0.7529411764705882;
1249 color.b = 0.8705882352941177;
1255 text =
"Single Mode";
1258 text =
"Continuous Mode";
1261 text =
"Stack Mode";
1265 jsk_rviz_plugins::OverlayText
msg;
1271 msg.bg_color.a = 0.0;
1272 msg.fg_color = color;
1282 jsk_footstep_planner::SetHeuristicPath srv_arg;
1284 geometry_msgs::Point
p;
1289 srv_arg.request.segments.push_back(
p);
1292 geometry_msgs::Point
p;
1295 FootstepVec tl = goal_pose_pair->midcoords().translation();
1299 srv_arg.request.segments.push_back(
p);
1303 ROS_ERROR(
"Service: failed to call footstep_planner/set_heuristic_path");