00001 // -*- mode: c++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2015, JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 #include <ros/ros.h> 00037 #include <interactive_markers/interactive_marker_server.h> 00038 00039 #include <jsk_recognition_msgs/PolygonArray.h> 00040 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 00041 #include <jsk_interactive_marker/FootstepMarkerConfig.h> 00042 00043 #include <interactive_markers/menu_handler.h> 00044 #include <jsk_interactive_marker/SetPose.h> 00045 #include <jsk_interactive_marker/MarkerSetPose.h> 00046 #include <interactive_markers/menu_handler.h> 00047 00048 #include <geometry_msgs/PointStamped.h> 00049 #include <message_filters/subscriber.h> 00050 #include <message_filters/time_synchronizer.h> 00051 #include <message_filters/synchronizer.h> 00052 00053 #include <tf/transform_listener.h> 00054 #include <actionlib/client/simple_action_client.h> 00055 #include <jsk_footstep_msgs/PlanFootstepsAction.h> 00056 #include <jsk_footstep_msgs/ExecFootstepsAction.h> 00057 #include <geometry_msgs/Polygon.h> 00058 #include <std_msgs/UInt8.h> 00059 #include <std_msgs/Empty.h> 00060 #include <jsk_recognition_msgs/SimpleOccupancyGridArray.h> 00061 #include <dynamic_reconfigure/server.h> 00062 00063 class FootstepMarker { 00064 public: 00065 typedef jsk_interactive_marker::FootstepMarkerConfig Config; 00066 FootstepMarker(); 00067 virtual ~FootstepMarker(); 00068 void updateInitialFootstep(); 00069 typedef actionlib::SimpleActionClient<jsk_footstep_msgs::PlanFootstepsAction> 00070 PlanningActionClient; 00071 typedef actionlib::SimpleActionClient<jsk_footstep_msgs::ExecFootstepsAction> 00072 ExecuteActionClient; 00073 typedef jsk_footstep_msgs::PlanFootstepsResult PlanResult; 00074 protected: 00075 void initializeInteractiveMarker(); 00076 void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00077 void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00078 void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg); 00079 void menuCommandCB(const std_msgs::UInt8::ConstPtr& msg); 00080 void executeCB(const std_msgs::Empty::ConstPtr& msg); 00081 void resumeCB(const std_msgs::Empty::ConstPtr& msg); 00082 void planDoneCB(const actionlib::SimpleClientGoalState &state, 00083 const PlanResult::ConstPtr &result); 00084 void processMenuFeedback(uint8_t id); 00085 geometry_msgs::Polygon computePolygon(uint8_t leg); 00086 void snapLegs(); 00087 geometry_msgs::Pose computeLegTransformation(uint8_t leg); 00088 geometry_msgs::Pose getFootstepPose(bool leftp); 00089 void changePlannerHeuristic(const std::string& heuristic); 00090 void callEstimateOcclusion(); 00091 void cancelWalk(); 00092 void planIfPossible(); 00093 void resetLegPoses(); 00094 void lookGround(); 00095 void configCallback(Config& config, uint32_t level); 00096 boost::mutex plane_mutex_; 00097 boost::mutex plan_run_mutex_; 00098 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_; 00099 // projection to the planes 00100 bool projectMarkerToPlane(); 00101 00102 jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr latest_grids_; 00103 // read a geometry_msgs/pose from the parameter specified. 00104 // the format of the parameter is [x, y, z, xx, yy, zz, ww]. 00105 // where x, y and z means position and xx, yy, zz and ww means 00106 // orientation. 00107 void readPoseParam(ros::NodeHandle& pnh, const std::string param, 00108 tf::Transform& offset); 00109 00110 // execute footstep 00111 // sending action goal to footstep controller 00112 void executeFootstep(); 00113 void resumeFootstep(); 00114 00115 void projectionCallback(const geometry_msgs::PoseStamped& pose); 00116 00117 visualization_msgs::Marker makeFootstepMarker(geometry_msgs::Pose pose); 00118 00119 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server_; 00120 interactive_markers::MenuHandler menu_handler_; 00121 double foot_size_x_; 00122 double foot_size_y_; 00123 double foot_size_z_; 00124 double footstep_margin_; 00125 std::string marker_frame_id_; 00126 geometry_msgs::PoseStamped marker_pose_; 00127 ros::Subscriber move_marker_sub_; 00128 ros::Subscriber menu_command_sub_; 00129 ros::Subscriber exec_sub_; 00130 ros::Subscriber resume_sub_; 00131 ros::Subscriber projection_sub_; 00132 ros::Publisher project_footprint_pub_; 00133 ros::Publisher snapped_pose_pub_; 00134 ros::Publisher current_pose_pub_; 00135 ros::Publisher footstep_pub_; 00136 ros::ServiceClient snapit_client_; 00137 ros::ServiceClient estimate_occlusion_client_; 00138 boost::shared_ptr<tf::TransformListener> tf_listener_; 00139 PlanningActionClient ac_; 00140 ExecuteActionClient ac_exec_; 00141 bool use_projection_service_; 00142 bool use_projection_topic_; 00143 bool show_6dof_control_; 00144 bool use_footstep_planner_; 00145 bool use_footstep_controller_; 00146 bool plan_run_; 00147 bool use_plane_snap_; 00148 bool wait_snapit_server_; 00149 bool use_initial_footstep_tf_; 00150 bool use_initial_reference_; 00151 bool always_planning_; 00152 bool lleg_first_; 00153 std::string initial_reference_frame_; 00154 geometry_msgs::Pose lleg_pose_; 00155 geometry_msgs::Pose rleg_pose_; 00156 geometry_msgs::Pose lleg_initial_pose_; 00157 geometry_msgs::Pose rleg_initial_pose_; 00158 tf::Transform lleg_offset_; 00159 tf::Transform rleg_offset_; 00160 std::string lfoot_frame_id_; 00161 std::string rfoot_frame_id_; 00162 00163 // footstep plannner result 00164 PlanResult::ConstPtr plan_result_; 00165 };