36 #define BOOST_PARAMETER_MAX_ARITY 7    42 #include <jsk_footstep_msgs/PlanFootstepsGoal.h>    43 #include <jsk_footstep_msgs/PlanFootstepsResult.h>    44 #include <std_srvs/Empty.h>    45 #include <jsk_recognition_msgs/CallSnapIt.h>    46 #include <Eigen/StdVector>    52 #include <jsk_interactive_marker/SnapFootPrint.h>    53 #include <jsk_interactive_marker/SnapFootPrintInput.h>    54 #include <jsk_interactive_marker/SetHeuristic.h>    58 ac_(
"footstep_planner", true), ac_exec_(
"footstep_controller", true),
    59 plan_run_(false), lleg_first_(true) {
    64   srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
    65   typename dynamic_reconfigure::Server<Config>::CallbackType 
f =
    67   srv_->setCallback (f);
    91   pnh.
param(
"no_wait", nowait, 
true);
   108     ROS_INFO(
"initial_reference_frame is not specified ");
   165         marker_pose_.pose.position.x = transform.getOrigin().x();
   166         marker_pose_.pose.position.y = transform.getOrigin().y();
   167         marker_pose_.pose.position.z = transform.getOrigin().z();
   168         marker_pose_.pose.orientation.x = transform.getRotation().x();
   169         marker_pose_.pose.orientation.y = transform.getRotation().y();
   170         marker_pose_.pose.orientation.z = transform.getRotation().z();
   171         marker_pose_.pose.orientation.w = transform.getRotation().w();
   175         ROS_ERROR(
"Failed to lookup transformation: %s", e.what());
   183     ROS_INFO(
"waiting planner server...");
   185     ROS_INFO(
"found planner server...");
   188     ROS_INFO(
"waiting controller server...");
   190     ROS_INFO(
"found controller server...");
   212         ROS_ERROR(
"Failed to lookup transformation: %s", e.what());
   239     return (
double)((int)val);
   250   geometry_msgs::Pose 
pose;
   252     pnh.
param(param, v, v);
   298   geometry_msgs::Pose new_pose;
   299   jsk_recognition_msgs::CallSnapIt 
srv;
   306     Eigen::Affine3d 
A, 
T, 
B, B_prime;
   309     if (leg == jsk_footstep_msgs::Footstep::LEFT) {
   312     else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
   315     B_prime = A.inverse() * T * A * B;
   335   geometry_msgs::Polygon polygon;
   338   std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > points;
   344   Eigen::Affine3d marker_pose_eigen;
   345   Eigen::Affine3d leg_pose_eigen;
   347   if (leg == jsk_footstep_msgs::Footstep::LEFT) {
   350   else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
   354   for (
size_t i = 0; i < points.size(); i++) {
   355     Eigen::Vector3d point = points[i];
   356     Eigen::Vector3d new_point = marker_pose_eigen * leg_pose_eigen * point;
   357     geometry_msgs::Point32 point_msg;
   358     point_msg.x = new_point[0];
   359     point_msg.y = new_point[1];
   360     point_msg.z = new_point[2];
   361     polygon.points.push_back(point_msg);
   391     Eigen::Affine3d le, re;
   401     ROS_ERROR(
"Failed to lookup transformation: %s", e.what());
   407   std_srvs::Empty empty;
   409     ROS_INFO(
"Finished to look ground");
   423   switch (menu_entry_id) {
   469   jsk_interactive_marker::SetHeuristic heuristic_req;
   470   heuristic_req.request.heuristic = heuristic;
   475     ROS_INFO(
"Success to set heuristic: %s", heuristic.c_str());
   495     jsk_interactive_marker::SnapFootPrint snap;
   497     snap.request.lleg_pose.orientation.w = 1.0;
   498     snap.request.rleg_pose.orientation.w = 1.0;
   503       geometry_msgs::PoseStamped resolved_pose;
   505                                   snap.response.snapped_pose,
   508       Eigen::Vector3d projected_point, marker_point;
   511       if ((projected_point - marker_point).norm() < 0.3) {
   512         server_->setPose(
"footstep_marker", resolved_pose.pose);
   524       ROS_WARN(
"Failed to snap footprint");
   529     jsk_interactive_marker::SnapFootPrintInput 
msg;
   531     msg.lleg_pose.orientation.w = 1.0;
   532     msg.rleg_pose.orientation.w = 1.0;
   550   bool skip_plan = 
false;
   551   geometry_msgs::PoseStamped input_pose;
   554     if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP) {
   559     if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP && !skip_plan) {
   564     ROS_ERROR(
"Failed to lookup transformation: %s", e.what());
   577   jsk_footstep_msgs::ExecFootstepsGoal goal;
   578   goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::RESUME;
   584   geometry_msgs::PoseStamped resolved_pose;
   589   Eigen::Vector3d projected_point, marker_point;
   592   if ((projected_point - marker_point).norm() < 0.3) {
   609     ROS_ERROR(
"no planner result is available");
   614   jsk_footstep_msgs::ExecFootstepsGoal goal;
   632     jsk_footstep_msgs::PlanFootstepsGoal goal;
   633     jsk_footstep_msgs::FootstepArray goal_footstep;
   635     goal_footstep.header.stamp = 
ros::Time(0.0);
   636     jsk_footstep_msgs::Footstep goal_left;
   637     goal_left.leg = jsk_footstep_msgs::Footstep::LEFT;
   642     jsk_footstep_msgs::Footstep goal_right;
   644     goal_right.leg = jsk_footstep_msgs::Footstep::RIGHT;
   648     goal_footstep.footsteps.push_back(goal_left);
   649     goal_footstep.footsteps.push_back(goal_right);
   650     goal.goal_footstep = goal_footstep;
   651     jsk_footstep_msgs::FootstepArray initial_footstep;
   653     initial_footstep.header.stamp = 
ros::Time(0.0);
   655     jsk_footstep_msgs::Footstep initial_left;
   656     initial_left.leg = jsk_footstep_msgs::Footstep::LEFT;
   662     jsk_footstep_msgs::Footstep initial_right;
   663     initial_right.leg = jsk_footstep_msgs::Footstep::RIGHT;
   669       initial_footstep.footsteps.push_back(initial_left);
   670       initial_footstep.footsteps.push_back(initial_right);
   673       initial_footstep.footsteps.push_back(initial_right);
   674       initial_footstep.footsteps.push_back(initial_left);
   676     goal.initial_footstep = initial_footstep;
   682                                  const PlanResult::ConstPtr &result)
   693   tf::Vector3 offset(0, 0, 0);
   712   tf::Transform footstep_transform = marker_origin * offset_trans;
   713   geometry_msgs::Pose ret;
   714   ret.position.x = footstep_transform.
getOrigin()[0];
   715   ret.position.y = footstep_transform.
getOrigin()[1];
   716   ret.position.z = footstep_transform.
getOrigin()[2];
   717   ret.orientation.x = footstep_transform.
getRotation()[0];
   718   ret.orientation.y = footstep_transform.
getRotation()[1];
   719   ret.orientation.z = footstep_transform.
getRotation()[2];
   720   ret.orientation.w = footstep_transform.
getRotation()[3];
   726   geometry_msgs::PoseStamped transformed_pose;
   730   bool skip_plan = 
false;
   740   server_->setPose(
"footstep_marker", transformed_pose.pose);
   749   visualization_msgs::Marker 
marker;
   750   marker.type = visualization_msgs::Marker::CUBE;
   754   marker.color.a = 1.0;
   760   visualization_msgs::InteractiveMarker int_marker;
   763   int_marker.name = 
"footstep_marker";
   766   left_box_marker.color.g = 1.0;
   768   visualization_msgs::InteractiveMarkerControl left_box_control;
   769   left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   770   left_box_control.always_visible = 
true;
   771   left_box_control.markers.push_back( left_box_marker );
   773   int_marker.controls.push_back( left_box_control );
   776   right_box_marker.color.r = 1.0;
   778   visualization_msgs::InteractiveMarkerControl right_box_control;
   779   right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   780   right_box_control.always_visible = 
true;
   781   right_box_control.markers.push_back( right_box_marker );
   783   int_marker.controls.push_back( right_box_control );
   797   visualization_msgs::InteractiveMarker initial_lleg_int_marker;
   799   initial_lleg_int_marker.name = 
"left_initial_footstep_marker";
   800   initial_lleg_int_marker.pose.orientation.w = 1.0;
   802   initial_left_marker.color.g = 1.0;
   804   visualization_msgs::InteractiveMarkerControl initial_left_box_control;
   805   initial_left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   806   initial_left_box_control.always_visible = 
true;
   807   initial_left_box_control.markers.push_back(initial_left_marker);
   809   initial_lleg_int_marker.controls.push_back( initial_left_box_control );
   810   server_->insert(initial_lleg_int_marker,
   813   visualization_msgs::InteractiveMarker initial_rleg_int_marker;
   815   initial_rleg_int_marker.name = 
"right_initial_footstep_marker";
   816   initial_rleg_int_marker.pose.orientation.w = 1.0;
   818   initial_right_marker.color.r = 1.0;
   820   visualization_msgs::InteractiveMarkerControl initial_right_box_control;
   821   initial_right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   822   initial_right_box_control.always_visible = 
true;
   823   initial_right_box_control.markers.push_back(initial_right_marker);
   825   initial_rleg_int_marker.controls.push_back( initial_right_box_control );
   826   server_->insert(initial_rleg_int_marker,
   837 int main(
int argc, 
char** argv) {
   838   ros::init(argc, argv, 
"footstep_marker");
 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ResultConstPtr getResult() const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
void transformEigenToTF(Eigen::Affine3f &eigen, tf::Transform &t)
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL const std::string & getName()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool apply(InteractiveMarkerServer &server, const std::string &marker_name)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO_THROTTLE(period,...)
SimpleClientGoalState getState() const
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
bool getParam(const std::string &key, std::string &s) const
void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
bool hasParam(const std::string &key) const
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
#define ROS_INFO_STREAM(args)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
void add3Dof2DControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
void add6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()