00001 // -*- mode: c++ -*- 00002 00003 #include <ros/ros.h> 00004 #include <interactive_markers/interactive_marker_server.h> 00005 00006 #include <jsk_pcl_ros/PolygonArray.h> 00007 #include <jsk_pcl_ros/ModelCoefficientsArray.h> 00008 00009 #include <interactive_markers/menu_handler.h> 00010 #include <jsk_interactive_marker/SetPose.h> 00011 #include <jsk_interactive_marker/MarkerSetPose.h> 00012 #include <interactive_markers/menu_handler.h> 00013 00014 #include <geometry_msgs/PointStamped.h> 00015 #include <message_filters/subscriber.h> 00016 #include <message_filters/time_synchronizer.h> 00017 #include <message_filters/synchronizer.h> 00018 00019 #include <tf/transform_listener.h> 00020 #include <actionlib/client/simple_action_client.h> 00021 #include <jsk_footstep_msgs/PlanFootstepsAction.h> 00022 #include <jsk_footstep_msgs/ExecFootstepsAction.h> 00023 #include <geometry_msgs/Polygon.h> 00024 #include <std_msgs/UInt8.h> 00025 #include <std_msgs/Empty.h> 00026 00027 class FootstepMarker { 00028 public: 00029 FootstepMarker(); 00030 virtual ~FootstepMarker(); 00031 void updateInitialFootstep(); 00032 typedef message_filters::sync_policies::ExactTime< jsk_pcl_ros::PolygonArray, 00033 jsk_pcl_ros::ModelCoefficientsArray> PlaneSyncPolicy; 00034 typedef actionlib::SimpleActionClient<jsk_footstep_msgs::PlanFootstepsAction> 00035 PlanningActionClient; 00036 typedef actionlib::SimpleActionClient<jsk_footstep_msgs::ExecFootstepsAction> 00037 ExecuteActionClient; 00038 typedef jsk_footstep_msgs::PlanFootstepsResult PlanResult; 00039 protected: 00040 void initializeInteractiveMarker(); 00041 void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00042 void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00043 void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg); 00044 void menuCommandCB(const std_msgs::UInt8::ConstPtr& msg); 00045 void executeCB(const std_msgs::Empty::ConstPtr& msg); 00046 void resumeCB(const std_msgs::Empty::ConstPtr& msg); 00047 void planeCB(const jsk_pcl_ros::PolygonArray::ConstPtr& planes, 00048 const jsk_pcl_ros::ModelCoefficientsArray::ConstPtr& coefficients); 00049 void planDoneCB(const actionlib::SimpleClientGoalState &state, 00050 const PlanResult::ConstPtr &result); 00051 void processMenuFeedback(uint8_t id); 00052 geometry_msgs::Polygon computePolygon(uint8_t leg); 00053 void snapLegs(); 00054 geometry_msgs::Pose computeLegTransformation(uint8_t leg); 00055 geometry_msgs::Pose getFootstepPose(bool leftp); 00056 void callEstimateOcclusion(); 00057 void cancelWalk(); 00058 void planIfPossible(); 00059 void resetLegPoses(); 00060 boost::mutex plane_mutex_; 00061 boost::mutex plan_run_mutex_; 00062 00063 // projection to the planes 00064 bool projectMarkerToPlane(); 00065 void transformPolygon(const geometry_msgs::PolygonStamped& polygon, 00066 const std_msgs::Header& target_header, 00067 std::vector<geometry_msgs::PointStamped>& output_points); 00068 double projectPoseToPlane(const std::vector<geometry_msgs::PointStamped>& polygon, 00069 const geometry_msgs::PoseStamped& point, 00070 geometry_msgs::PoseStamped& foot); 00071 00072 jsk_pcl_ros::PolygonArray::ConstPtr latest_planes_; 00073 jsk_pcl_ros::ModelCoefficientsArray::ConstPtr latest_coefficients_; 00074 // read a geometry_msgs/pose from the parameter specified. 00075 // the format of the parameter is [x, y, z, xx, yy, zz, ww]. 00076 // where x, y and z means position and xx, yy, zz and ww means 00077 // orientation. 00078 void readPoseParam(ros::NodeHandle& pnh, const std::string param, 00079 tf::Transform& offset); 00080 00081 // execute footstep 00082 // sending action goal to footstep controller 00083 void executeFootstep(); 00084 void resumeFootstep(); 00085 00086 visualization_msgs::Marker makeFootstepMarker(geometry_msgs::Pose pose); 00087 00088 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server_; 00089 interactive_markers::MenuHandler menu_handler_; 00090 double foot_size_x_; 00091 double foot_size_y_; 00092 double foot_size_z_; 00093 double footstep_margin_; 00094 std::string marker_frame_id_; 00095 geometry_msgs::PoseStamped marker_pose_; 00096 ros::Subscriber move_marker_sub_; 00097 ros::Subscriber menu_command_sub_; 00098 ros::Subscriber exec_sub_; 00099 ros::Subscriber resume_sub_; 00100 message_filters::Subscriber<jsk_pcl_ros::PolygonArray> polygons_sub_; 00101 message_filters::Subscriber<jsk_pcl_ros::ModelCoefficientsArray> coefficients_sub_; 00102 boost::shared_ptr<message_filters::Synchronizer<PlaneSyncPolicy> >sync_; 00103 00104 ros::Publisher snapped_pose_pub_; 00105 ros::Publisher footstep_pub_; 00106 ros::ServiceClient snapit_client_; 00107 ros::ServiceClient estimate_occlusion_client_; 00108 boost::shared_ptr<tf::TransformListener> tf_listener_; 00109 PlanningActionClient ac_; 00110 ExecuteActionClient ac_exec_; 00111 bool show_6dof_control_; 00112 bool use_footstep_planner_; 00113 bool use_footstep_controller_; 00114 bool use_plane_snap_; 00115 bool plan_run_; 00116 bool wait_snapit_server_; 00117 bool use_initial_footstep_tf_; 00118 bool use_initial_reference_; 00119 std::string initial_reference_frame_; 00120 geometry_msgs::Pose lleg_pose_; 00121 geometry_msgs::Pose rleg_pose_; 00122 geometry_msgs::Pose lleg_initial_pose_; 00123 geometry_msgs::Pose rleg_initial_pose_; 00124 tf::Transform lleg_offset_; 00125 tf::Transform rleg_offset_; 00126 std::string lfoot_frame_id_; 00127 std::string rfoot_frame_id_; 00128 00129 // footstep plannner result 00130 PlanResult::ConstPtr plan_result_; 00131 };