πΉοΈ Target Navigation DEMO#
Launch a DEMO#
To launch the default DEMO of the Target Navigation, you can use the following command.
ros2 launch pal_advanced_navigation_demo pal_target_navigation_demo_1.launch.py robot_name:=<your_robot> base_type:=<your_base>
In this demo you will see the robot spawning some meters in front of an ArUco target with ID 0. The robot will detect it and navigate to it.
You can keep track of the tasksβ status by reading in the log. You can check the pose of the detected aruco in RViz with the /updated_goal. The detection can be also visualized with the /target_detector_server/image.
This DEMO is a simple ArUco navigation task, but you can create your own target navigation application by following the instructions below.
Create your own Traget Navigation DEMO#
If you want to create and launch your customized Target Navigation DEMO you should create your node and launch the DEMO like this:
- open a terminal and launch the following command:
ros2 launch pal_advanced_navigation_demo pal_target_navigation_demo_base.launch.py robot_name:=<your_robot> base_type:=<your_base>
- open another terminal and run your node:
ros2 run <your_demo_package> <your_target_navigation_demo_node>
After including all the necessary headers, you need to initialize the node and create the action client:
rclcpp::init(argc, argv);
auto node = std::make_shared<rclcpp::Node>("your_demo_node");
auto ac_target_nav =
rclcpp_action::create_client<pal_nav2_msgs::action::NavigateToTarget>(node, "navigate_to_target");
class TargetNavigationClient(Node):
def __init__(self):
super().__init__("your_demo_node")
self._action_client = ActionClient(self, NavigateToTarget,
"navigate_to_target")
Then you need to create the goal message and fill it with the behavior tree, the detector and the ID of the target to which you want to navigate.
pal_nav2_msgs::action::NavigateToTarget::Goal goal;
goal.target_id = 0;
goal.behavior_tree = "navigate_to_target";
goal.detector = "aruco_target_detector";
goal = NavigateToTarget::Goal()
goal.target_id = 0
goal.behavior_tree = "navigate_to_target"
goal.detector = "aruco_target_detector"
Finally, you need to send the goal to the action server and wait for the result.
auto future = ac_target_nav->async_send_goal(goal);
auto result = rclcpp::spin_until_future_complete(node, future);
if (result != rclcpp::FutureReturnCode::SUCCESS) {
RCLCPP_ERROR(node->get_logger(), "Failed to navigate to target");
return false;
}
self._send_goal_future = self.ac_target_nav.send_goal_async(goal)
self._send_goal_future.add_done_callback(self.goal_response_callback)
def goal_response_callback(self, future):
goal_handle = future.result()
if not goal_handle.accepted:
self.get_logger().error('Goal rejected')
rclpy.shutdown()
return
self.get_logger().info('Goal accepted')
self._get_result_future = goal_handle.get_result_async()
self._get_result_future.add_done_callback(self.get_result_callback)
def get_result_callback(self, future):
result = future.result().result
if result:
self.get_logger().info('Goal succeeded')
else:
self.get_logger().error('Goal failed')
rclpy.shutdown()