Contents Menu Expand Light mode Dark mode Auto light/dark mode
This is the documentation of ROS 2 PAL OS edge. Click here for PAL OS 25.01 stable or PAL OS 23.12 (ROS 1).
PAL OS 25.01 documentation
Logo
PAL OS 25.01 documentation

Capabilities and API

  • 🏁 Getting started
  • βš™οΈ Robot hardware
  • πŸ›  Robot management
  • πŸ“œ Developing applications
  • πŸ‘‹ Gestures and motions
  • 🧭 Navigation
  • 🦾 Manipulation
  • πŸ‘₯ Social perception
  • πŸ’¬ Communication
  • πŸ˜„ Interaction
  • πŸ’‘ Knowledge and reasoning
  • πŸ–₯️ User interfaces

Reference

  • PAL OS edge Highlights
  • PAL public skills API
  • PAL OS modules
  • Frequently Asked Questions
  • Glossary
  • Index
  • Tutorials
  • 🚧 Demos
  • List of ROS Topics
  • List of ROS Actions
  • List of ROS Services
  • List of ROS Nodes
  • List of ROS messages
  • List of ROS Parameters
Back to top

../_images/tiagopro-icon.png ../_images/tiago-head-icon.png ../_images/kangaroo-icon.png ../_images/tiago-icon.png ../_images/triago-icon.png ../_images/ari-icon.png ../_images/talos-icon.png ../_images/mobile-bases-icon.png

/navigate_to_zoneΒΆ

Caution

This documentation page has been auto-generated.

It may be missing some details.

/navigate_to_zone Quick Facts

Category

🧭 Navigation

Message type

pal_nav2_msgs/action/NavigateToZone

Nav2 Behavior implemented for PAL robots. It allows sendin a Navigation goal to the robot to reach a previously stored Zone. This behavior can be configured to reach the middle of the Zone or to suceed as soon as the robot enters the Zone.

For more information, check the πŸ›οΈ Environmental Annotations.

SERVER

  • global_behavior_server

Quick snippetsΒΆ

Send a goal from the command-lineΒΆ
$ ros2 action send_goal /navigate_to_zone pal_nav2_msgs/action/NavigateToZone # press Tab to complete the message prototype

How to use in your codeΒΆ

Call the action from a Python scriptΒΆ
#!/usr/bin/env python

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node

from pal_nav2_msgs.action import NavigateToZone

class NavigateToZoneActionClient(Node):

    def __init__(self):
        super().__init__('navigate_to_zone_client')
        self._action_client = ActionClient(self, NavigateToZone, '/navigate_to_zone')

    def send_goal(self, a, b):
        goal_msg = NavigateToZone.Goal()

        # TODO: adapt to the action's parameters
        # check the pal_nav2_msgs/action/NavigateToZoneGoal message
        # definition for the possible goal parameters
        # goal_msg.a = a
        # goal_msg.b = b

        self._action_client.wait_for_server()

        return self._action_client.send_goal_async(goal_msg)

if __name__ == '__main__':
    rclpy.init(args=args)

    action_client = NavigateToZoneActionClient()

    # TODO: adapt to your action's parameters
    future = action_client.send_goal(a, b)

    rclpy.spin_until_future_complete(action_client, future)

    rclpy.shutdown()
Call the action from a C++ programΒΆ
#include <functional>
#include <future>
#include <memory>
#include <string>
#include <sstream>
#include <chrono>

#include "pal_nav2_msgs/action/navigate_to_zone.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "rclcpp_components/register_node_macro.hpp"

using namespace std::chrono_literals;
using namespace std;

class NavigateToZoneActionClient : public rclcpp::Node
{
public:
  using NavigateToZone = pal_nav2_msgs::action::NavigateToZone;
  using GoalHandleNavigateToZone = rclcpp_action::ClientGoalHandle<NavigateToZone>;

  explicit NavigateToZoneActionClient(const rclcpp::NodeOptions & options)
  : Node("navigate_to_zone_action_client", options)
  {
    this->client_ptr_ = rclcpp_action::create_client<NavigateToZone>(
            this,
            "/navigate_to_zone");

    this->timer_ = this->create_wall_timer(
            500ms,
            bind(&NavigateToZoneActionClient::send_goal, this));
  }

  void send_goal()
  {
    using namespace std::placeholders;

    this->timer_->cancel();

    if (!this->client_ptr_->wait_for_action_server()) {
      RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting");
      rclcpp::shutdown();
    }

    auto goal_msg = NavigateToZone::Goal();

    // check the pal_nav2_msgs/action/NavigateToZoneGoal message
    // definition for the possible goal parameters
    // goal_msg.... = ...;

    RCLCPP_INFO(this->get_logger(), "Sending goal");

    auto send_goal_options = rclcpp_action::Client<NavigateToZone>::SendGoalOptions();

    send_goal_options.goal_response_callback =
        bind(&NavigateToZoneActionClient::goal_response_callback, this, _1);

    send_goal_options.feedback_callback =
        bind(&NavigateToZoneActionClient::feedback_callback, this, _1, _2);

    send_goal_options.result_callback =
        bind(&NavigateToZoneActionClient::result_callback, this, _1);


    this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
  }

private:
  rclcpp_action::Client<NavigateToZone>::SharedPtr client_ptr_;
  rclcpp::TimerBase::SharedPtr timer_;

  void goal_response_callback(const GoalHandleNavigateToZone::SharedPtr & goal_handle)
  {
    if (!goal_handle) {
      RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
    } else {
      RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
    }
  }

  void feedback_callback(
      GoalHandleNavigateToZone::SharedPtr,
      const shared_ptr<const NavigateToZone::Feedback> feedback)
  {
    stringstream ss;
    ss << "Next number in sequence received: ";
    for (auto number : feedback->partial_sequence) {
      ss << number << " ";
    }
    RCLCPP_INFO(this->get_logger(), ss.str().c_str());
  }

  void result_callback(const GoalHandleNavigateToZone::WrappedResult & result)
  {
    switch (result.code) {
      case rclcpp_action::ResultCode::SUCCEEDED:
          break;
      case rclcpp_action::ResultCode::ABORTED:
          RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
          return;
      case rclcpp_action::ResultCode::CANCELED:
          RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
          return;
      default:
          RCLCPP_ERROR(this->get_logger(), "Unknown result code");
          return;
    }
    stringstream ss;
    ss << "Result received: ";
    for (auto number : result.result->sequence) {
      ss << number << " ";
    }
    RCLCPP_INFO(this->get_logger(), ss.str().c_str());
    rclcpp::shutdown();
  }
};  // class NavigateToZoneActionClient


RCLCPP_COMPONENTS_REGISTER_NODE(NavigateToZoneActionClient)
Copyright © 2024, PAL Robotics
Made with Sphinx and @pradyunsg's Furo
On this page
  • /navigate_to_zone
    • Quick snippets
    • How to use in your code
πŸ›  Getting support