Skip to content

SLAM Navigation Service Interface


Localization-Related Interfaces

Merged Point Cloud Service Interface

Overview

This interface subscribes to the ROS 2 topic /merged_points to receive aggregated point cloud data from multiple solid-state LiDAR sensors.

Topic NameMessage TypeRole
/merged_pointssensor_msgs/msg/PointCloud2Subscriber

Message Structure & Field Description

The message structure follows sensor_msgs/msg/PointCloud2. For detailed field definitions, refer to the LiDAR Service Interface section.

Precautions

  1. Point cloud aggregation requires that the LiDAR ROS 2 node is properly launched and is publishing data to /livox/lidar.
  2. You can inspect the input topics of the aggregation node via:
plain
ros2 node info /pointcloud_accumulator_node

and verify whether topic data is being correctly received.

Downsampled Point Cloud Service Interface

Overview

This interface subscribes to the ROS 2 topic /downsampled_points to receive downsampled point cloud data, reducing computational load for downstream tasks.

Topic NameMessage TypeRole
/downsampled_pointssensor_msgs/msg/PointCloud2Subscriber

Message Structure & Field Description

Same as sensor_msgs/msg/PointCloud2. Refer to the LiDAR Service Interface for full schema.

Precautions

  1. This service depends on both /livox/lidar and /merged_points being actively published by the ROS 2 LiDAR nodes.

Relocalization Service Interface

Overview

This interface invokes the ROS 2 service /set_initialpose to set the robot's initial pose in the map frame during global relocalization.

Action NameAction TypeRole
set_initialposedaystar_navigation_msgs/srv/SetInitialPose请求Client

Message Structure

plain
# --- request ---
geometry_msgs/PoseWithCovarianceStamped init_pose
# --- response ---
bool result
geometry_msgs/PoseWithCovarianceStamped result_pose

Field Description

  • init_pose: Initial pose set during relocalization, including timestamp and covariance.
  • result: Boolean flag indicating success or failure of the relocalization attempt.
  • result_pose: The adjusted and verified pose returned after relocalization.

Precautions

  1. The initial pose can be obtained either by manually positioning the robot at a known location or by using RViz to interactively set the pose.
  2. Upon successful relocalization, the localization module will broadcast the coordinate transforms via the /tf topic, which will be used by the navigation and control modules.

Navigation and Control Interface

Intelligent Navigation Request Interface

Overview

This interface subscribes to the ROS 2 action /intelligent_navigate_to_pose to initiate intelligent navigation requests and configure related parameters for adaptive motion planning.

Action NameAction TypeRole
intelligent_navigat_to_posedaystar_navigation_msgs/action/IntelligentNavitateToPoseClient

Message Structure

bash
# --- goal ---
daystar_navigation_msgs/TravelParams travel_params      # Travel parameters
  daystar_navigation_msgs/SpeedMode speed_mode
  daystar_navigation_msgs/Gait gait
  daystar_navigation_msgs/ObstacleParams obstacle_params
    bool disable_body_obstacle_avoidance
  bool ignore_final_yaw
	daystar_navigation_msgs/NavMode nav_mode
  int8 direction_constraint
geometry_msgs/PoseStamped pose
bool should_stop
# --- result ---
string message
bool result
# --- feedback ---
geometry_msgs/PoseStamped current_pose
daystar_navigation_msgs/NavState current_state

Key Field Explanations

travel_params: Configurable parameters for navigation planning.

  • speed_mode: Sets the maximum allowed speed (2 = low, 1 = medium, 3 = high).
  • gait: Selects gait pattern (2 = diagonal trot, 5 = slope gait, 6 = stair-perception gait, 7 = normal stair gait).
  • height: Sets robot posture height (2 = low, 1 = normal, 3 = high).
  • obstacle_params.disable_body_obstacle_avoidance: Boolean switch to enable/disable body obstacle avoidance.
  • path_following_mode: Navigation mode (1/4 = line-following, 2 = free navigation, 3 = intelligent navigation).
  • direction_constraint: Motion direction constraint (3 = forward, 4 = reverse).

pose: Target position and orientation (in quaternion).

current_pose: Feedback pose from localization.

current_state: Feedback indicating current navigation state.

Test Example

  • Use the following command to send a test goal:
bash
ros2 action send_goal /nav/intelligent_navigate_to_pose daystar_navigation_msgs/action/IntelligentNavitateToPose "
travel_params:
  speed_mode:
    value: 2
  gait:
    gait: 5
  obstacle_params:
    disable_body_obstacle_avoidance: true
  path_following_mode: 4
  direction_constraint: 3	
  height: 1
pose:
  header:
    stamp:
      sec: 0
      nanosec: 0
    frame_id: 'map'
  pose:
    position:
      x: <target_pose_.x>
      y: <target_pose_.y>
      z: <target_pose_.z>
    orientation:
      x: <target_ori_.x>
      y: <target_ori_.y>
      z: <target_ori_.z>
      w: <target_ori_.w>
"

Precautions

  • Ensure that all relevant ROS 2 nodes and the action_server are properly launched.
  • The goal message must strictly follow the daystar_navigation_msgs/action/IntelligentNavitateToPose message definition.
  • Verify that the gait mode, direction constraint, and navigation mode settings match the requirements and safety constraints of your testing environment.

Path Planner Invocation Interface

Overview

This interface is used to send action requests to the ROS 2 navigation planner via the /compute_path_to_pose action, enabling path planning computation from a start pose to a target goal pose.

Action NameAction TypeRole
/compute_path_to_posenav2_msgs/action/ComputePathToPoseClient

Message Structure

bash
# goal
geometry_msgs/PoseStamped goal
geometry_msgs/PoseStamped start
string planner_id
bool use_start
# --- result ---
nav_msgs/Path path
builtin_interfaces/Duration planning_time

Key Field Descriptions

  • goal:The target position and orientation for the robot to reach, represented as a time-stamped PoseStamped message.
  • start:The initial pose from which to start planning. Also a PoseStamped message with timestamp.
  • planner_id:Identifier for selecting a specific planner plugin (e.g., "GridBased", "SmacPlanner", etc.). If empty, the default planner is used.
  • use_start:Determines whether to use the explicitly provided start pose.
  • true: Use the given start field.
  • false: Use the robot's current pose as the start of the path.
  • path:The result path as a nav_msgs/Path message, which contains a header and an array of PoseStamped elements representing waypoints along the planned route.
  • planning_time:Duration taken by the planner to compute the path.

Controller Invocation Interface

Overview

This interface is used to send action requests to the ROS 2 navigation controller via the /follow_path action. It enables the controller module to compute control commands that guide the robot along a given path.

Action NameAction TypeRole
/follow_pathnav2_msgs/action/FollowPathClient

Message Structure

bash
# --- goal ---
nav_msgs/Path path
string controller_id
string goal_checker_id
# --- result ---
std_msgs/Empty result
# --- feedback ---
float32 distance_to_goal
float32 speed

Key Field Descriptions

  • path:The navigation path that the robot is expected to follow, represented by a nav_msgs/Path message.
    This includes:
    • A header with timestamp and frame ID
    • A poses[] array of PoseStamped messages, each representing a waypoint along the path
  • controller_id:Specifies the ID of the controller plugin to use (e.g., "FollowPathController", "RegulatedPurePursuitController").
  • goal_checker_id:Specifies the ID of the goal checker plugin that determines if the robot has reached its goal (e.g., "simple_goal_checker").
  • distance_to_goal:Real-time feedback indicating how far the robot is from the final goal pose (in meters).
  • speed:Real-time feedback of the robot's current linear speed (in meters per second).