27 : ivIdFootRight(
"/r_sole"),
28 ivIdFootLeft(
"/l_sole"),
30 ivExecutingFootsteps(false),
31 ivFootstepsExecution(
"footsteps_execution", true),
42 nh_public.
serviceClient<humanoid_nav_msgs::StepTargetService>(
50 nh_public.
subscribe<nav_msgs::OccupancyGrid>(
53 nh_public.
subscribe<geometry_msgs::PoseStamped>(
82 nh_private.
getParam(
"step_range/x", step_range_x);
83 nh_private.
getParam(
"step_range/y", step_range_y);
85 ROS_ERROR(
"Error reading footsteps/x from config file.");
87 ROS_ERROR(
"Error reading footsteps/y from config file.");
88 if (step_range_x.
size() != step_range_y.
size())
90 ROS_ERROR(
"Step range points have different size. Exit!");
97 for (
int i = 0; i < step_range_x.
size(); ++i)
99 x = (double)step_range_x[i];
100 y = (double)step_range_y[i];
101 ivStepRange.push_back(std::pair<double, double>(x, y));
149 else if (path_existed)
151 ROS_INFO(
"Replanning unsuccessful. Reseting previous planning " 191 ROS_INFO(
"Start walking towards the goal.");
193 humanoid_nav_msgs::StepTarget
step;
194 humanoid_nav_msgs::StepTargetService step_srv;
197 std::string support_foot_id;
207 const State* from_planned = to_planned.base();
213 boost::this_thread::interruption_point();
215 catch (
const boost::thread_interrupted&)
231 if (
getFootstep(from, *from_planned, *to_planned, &step))
233 step_srv.request.step = step;
239 ROS_INFO(
"Footstep cannot be performed. Replanning necessary.");
253 from_planned = to_planned.base();
256 ROS_INFO(
"Succeeded walking to the goal.\n");
275 humanoid_nav_msgs::ExecFootstepsGoal
goal;
311 ROS_INFO(
"Start walking towards the goal.");
318 const humanoid_nav_msgs::ExecFootstepsResultConstPtr& result)
321 ROS_INFO(
"Succeeded walking to the goal.");
323 ROS_INFO(
"Preempted walking to the goal.");
326 ROS_INFO(
"Failed walking to the goal.");
335 const humanoid_nav_msgs::ExecFootstepsFeedbackConstPtr& fb)
339 if (executed_steps_idx < 0)
363 humanoid_nav_msgs::ExecFootstepsGoal
goal;
397 ROS_DEBUG(
"Footstep execution incorrect.");
399 humanoid_nav_msgs::ExecFootstepsGoal
goal;
404 ROS_INFO(
"Try to reach calculated path.");
430 ROS_DEBUG(
"planned (%f, %f, %f, %i) vs. executed (%f, %f, %f, %i)",
433 executed.getX(), executed.getY(), executed.getTheta(),
442 ROS_DEBUG(
"Invalid step. Wait next step update before declaring" 450 const geometry_msgs::PoseStampedConstPtr& goal_pose)
455 ROS_INFO(
"Already performing a navigation task. Wait until it is " 474 const nav_msgs::OccupancyGridConstPtr& occupancy_map)
505 return setGoal(goal_pose->pose.position.x,
506 goal_pose->pose.position.y,
550 ROS_INFO(
"Robot standing at (%f, %f, %f, %i) (%f, %f, %f, %i).",
560 const State& from_planned,
562 humanoid_nav_msgs::StepTarget* footstep)
574 footstep->leg = humanoid_nav_msgs::StepTarget::left;
576 footstep->leg = humanoid_nav_msgs::StepTarget::right;
591 float step_diff_x = fabs(from.
getOrigin().
x() - from_planned.
getX());
592 float step_diff_y = fabs(from.
getOrigin().
y() - from_planned.
getY());
593 float step_diff_theta = fabs(
637 const State& current_support_leg,
int starting_step_num,
638 std::vector<humanoid_nav_msgs::StepTarget>& footsteps)
640 humanoid_nav_msgs::StepTarget footstep;
646 const State* from_planned = to_planned.base();
650 if (
getFootstep(last, *from_planned, *to_planned, &footstep))
652 footsteps.push_back(footstep);
656 ROS_ERROR(
"Calculated path cannot be performed!");
661 tf::Point(to_planned->getX(), to_planned->getY(), 0.0));
662 from_planned = to_planned.base();
671 const std::string& world_frame_id,
682 stamped_foot_transform);
686 ROS_WARN(
"Failed to obtain FootTransform from tf (%s)", e.what());
699 float b_x,
float b_y,
float b_theta)
710 const humanoid_nav_msgs::ClipFootstep& step)
713 step.request.step.pose.y,
714 step.request.step.pose.theta,
715 step.response.step.pose.x,
716 step.response.step.pose.y,
717 step.response.step.pose.theta);
723 const State& executed)
734 float step_x = footstep.pose.x;
735 float step_y = footstep.pose.y;
736 float step_theta = footstep.pose.theta;
738 if (footstep.leg == humanoid_nav_msgs::StepTarget::right)
741 step_theta = -step_theta;
764 for(
unsigned int i = 0; i <
ivStepRange.size() - 1; ++i)
771 float vt = (float)(step_y -
ivStepRange[i].second) /
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static double getYaw(const Quaternion &bt_q)
bool call(MReq &req, MRes &res)
Type const & getType() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
static Quaternion createQuaternionFromYaw(double yaw)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
bool getParam(const std::string &key, std::string &s) const
def shortest_angular_distance(from_angle, to_angle)