Skip to content

SLAM Navigation Service Interface


1. Positioning Related Interfaces

1.1 Point Cloud Data Aggregation Service Interface

1.1.1 Introduction

This interface is used to subscribe to ROS2 merged_points topic to obtain point cloud data after polymerization of multor solid-state radar

Action NameAction Message TypeRole
merged_pointssensor_msgs/msg/PointCloud2Subscriber

1.1.2 Message Structure & Main Field Description

For the message structure and field description of sensor_msgs/msg/PointCloud2, see LiDAR Service Interface document description.

1.1.3 Precautions

The prerequisite for point cloud data aggregation is that the LiDAR ROS2 node is started and the livox/lidar topic data is published. You can pass ros2 node info pointcloud_accumutor_node view the input topic of the interface node and check whether the topic data is normal.

1.2 Point Cloud Downsampling Service Interface

1.2.1 Introduction

This interface is used to subscribe to ROS2 downsampled_points topic to obtain the point cloud data after downsampling.

Action NameAction Message TypeRole
downsampled_pointssensor_msgs/msg/PointCloud2Subscriber

1.2.2 Message Structure & Main Field Description

For the message structure and field description of sensor_msgs/msg/PointCloud2, see LiDAR Service Interface document description.

1.2.3 Precautions

The prerequisite for the point cloud downsampling service interface to take effect is that the LiDAR ROS2 node is normally started and the topic data is published. livox/lidar and merged_points topic.

1.3 Relocation Interface

1.3.1 Introduction

This interface is used to request ROS2 set_initialpose service service to set the initial position of the robot in the map coordinate system during relocation.

Action NameAction Message TypeRole
set_initialposedaystar_navigation_msgs/srv/SetInitialPoseRequester

1.3.2 Message Structure

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

1.3.3 Main Field Description

init_pose : The initial pose set at the time of relocation, with the pose message with timestamp and covariance.

result : Flag bit of whether the repositioning was successful.

result_pose : Actual pose information after verification of relocation adjustment.

1.3.4 Precautions

  1. The initial pose for repositioning can be acquired by moving the robot to a known point and then, or by rviz.

  2. After the relocation is successful, the positioning module will pass tf topic publishes the conversion relationship between coordinate systems and applies it to the navigation regulation process.

2. Navigation Gauge Interface

2.1 Intelligent Navigation Initiation Interface

2.1.1 Introduction

This interface is used to subscribe to ROS2 /Very action Request for intelligent navigation requests and related configuration settings.

Action NameAction Message TypeRole
kandaystar_navigation_msgs/action/IntelligentNavitateToPoseRequester

2.1.2 Message Structure

bash
# --- goal ---
daystar_navigation_msgs/TravelParams travel_params      # 行程参数
  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

2.1.3 Main Field Description

travel_params : Travel parameters

  • speed_mode : Speed mode setting, limit the maximum speed; Low speed 2, the default , medium speed 1 , high speed 3
  • gait: Gait mode settings, diagonal trot gait 2 ramp gait 5 , perceived stair gait 6 normal stair gait 7
  • height : Altitude mode setting, low profile 2 normal attitude 1 , high profile 3
  • obstacle_params : Obstacle mode setting
    • disable_body_obstacle_avoidance : Whether to stop the parking barrier, stop true , enable false
  • path_following: Ing_mode navigation mode settings, patrol mode 1,4 free navigation mode 2 , intelligent navigation mode 3
  • direction_constraint : Forward direction setting, going 3 , go backwards 4

pose: Target pose, including target position position and orientation in quaternion form orientation.

current_pose : Feedback information indicating the current positioning pose.

current_state: Feedback information, indicating the current navigation status.

2.1.4 Test Method

  • Use the following command to make a request to Smart Navigation:
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>
"

2.1.5 Precautions

  • Make sure that the ROS2 node is started and the action_server starts normally.
  • The format of the published message must be strictly daystar_navigation_msgs/action/IntelligentNavitateToPose the definition of the message type.
  • Be sure to verify that the relevant attributes such as gait pattern settings and heading settings are compatible with the Test environment.

2.2 Planner Initiated Interface

2.2.1 Introduction

This interface is used for the ROS2 navigation planner. compute_path_to_pose action Request for the navigation planner module to solve.

Action NameAction Message TypeRole
compute_path_to_posenav2_msgs/action/ComputePathToPoseRequester

2.2.2 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

2.2.3 Main Field Description

  • goal : The target position and direction that the robot needs to reach, which is a pose message with a timestamp.
  • start : The starting position and direction of the robot to start planning, which is a pose message with a timestamp.
  • planner_id: Used to specify the ID of the path planner used.
  • use_start: Used to indicate whether to use the provided start pose as a starting point for planning. true provided for the use start pose; false to use the robot's current position as a planning starting point.
  • path: Path message representing the path generated by the planner. path message contains a header and a poses array, each element in the array is a PoseStamped which represents a point in the path.
  • planning_time : Represents the time it took for the planner to generate the path.

2.3 Controller Initiated Interface

2.3.1 Introduction

This interface is used for the ROS2 navigation controller follow_path action Request for navigation controller module solution.

Action NameAction Message TypeRole
follow_pathnav2_msgs/action/FollowPathRequester

2.3.2 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

2.3.2 Main Field Description

  • path : Path message, indicating the path that the robot needs to follow. path message contains a header (Timestamp and coordinate system information) and a poses array, each element in the array is a PoseStamped which represents a point in the path.
  • controller_id: Specifies the controller ID used.
  • goal_checker_id: Specifies the target inspector ID used.
  • distance_to_goal: Feedback information, the remaining distance of the robot from the target position.
  • speed: Feedback information, the current movement speed of the robot.