navground_ros#
- package navground_ros#
This ROS2 provides a ROS2 compliant interface to
navground_core.
Executables#
- executable controller#
Executes a
ROSControllerNodeusing a single threaded executor.
Launch files#
- launch file navigation.launch#
- Arguments:
kinematics_type – [Default:
2WDiff]kinematics_max_speed – [Default:
0.3]kinematics_max_angular_speed – [Default:
0.2]kinematics_wheel_axis – [Default:
1.0]radius – [Default:
0.3]heading – [Default:
idle]behavior – [Default:
HL]optimal_speed – [Default:
0.3]optimal_angular_speed – [Default:
0.3]rotation_tau – [Default:
0.5]horizon – [Default:
1.0]safety_margin – [Default:
0.1]speed_tolerance – [Default:
0.05]hl_tau – [Default:
0.5]hl_eta – [Default:
0.5]hl_aperture – [Default:
3.14]hl_resolution – [Default:
30]orca_time_horizon – [Default:
1.0]altitude_optimal_speed – [Default:
0.1]altitude_tau – [Default:
1.0]drawing – [Default:
false]publish_cmd_stamped – [Default:
false]rate – [Default:
10.0]odom_topic – [Default:
odom]frame_id – [Default:
world]
Nodes#
ROSControllerNode#
- node RoboMasterROS#
This ROS2 node exposes a ROS2-compliant interface to a navigation controller
navground::core::Controller3.Summary
Parameters
Subscriptions
Publishers
Action servers
Parameters#
-
parameter rate float [Default:
10.0]# Control update rate in Hz. Should be positive.
-
parameter frame_id str [Default:
world]# Name of the TF frame where to perform navigation computations.
-
parameter publish_cmd_stamped bool [Default:
false]# Whether to publish a TwistStamped in frame_id instead of a Twist in body frame.
-
parameter drawing bool [Default:
false] # Whether to publish visual markers to display debug information to RViz.
Kinematics#
-
parameter kinematics.type str [Default:
"HL"]# Name of the kinematics, see
navground::core::Kinematics. Should be one of the registered names.
-
parameter kinematics.max_speed float [Default:
1.0]# Maximal speed, see
navground::core::Kinematics::get_max_speed(). Should be positive.
-
parameter kinematics.max_angular_speed float [Default:
1.0]# Maximal angular speed, see
navground::core::Kinematics::get_max_angular_speed(). Should be positive.
-
parameter kinematics.wheel_axis float [Default:
1.0]# Wheel axis, see
navground::core::TwoWheelsDifferentialDriveKinematics::get_wheel_axis(). Should be positive. Only relevant for some kinematics.
Behavior#
-
parameter radius float [Default:
0.0]# The radius of the agent, see
navground::core::Behavior::get_radius(). Should be positive.
-
parameter behavior str [Default:
"HL"] # Name of the navigation behavior, see
navground::core::Behavior. Should be one of the registered names.
-
parameter heading str [Default:
idle] # Heading behavior, see
navground::core::Behavior::get_heading_behavior(). One of “idle”, “target_point”, “target_angular_speed”, or “velocity”.
-
parameter horizon float [Default:
1.0] # Horizon, see
navground::core::Behavior::get_horizon(). Should be positive.
-
parameter optimal_angular_speed float [Default:
0.3] # Optimal angular speed, see
navground::core::Behavior::get_optimal_angular_speed(). Should be positive.
-
parameter optimal_speed float [Default:
0.3] # Optimal speed, see
navground::core::Behavior::get_optimal_speed(). Should be positive.
-
parameter rotation_tau float [Default:
0.5] # Rotation relaxation time, see
navground::core::Behavior::get_rotation_tau(). Should be positive.
-
parameter safety_margin float [Default:
0.1] # Safety margin, see
navground::core::Behavior::get_safety_margin(). Should be positive.
HL behavior#
-
parameter hl.aperture float [Default:
3.141592741012] # Aperture, see
navground::core::HLBehavior::get_aperture(). Should be positive.
-
parameter hl.eta float [Default:
0.5] # Eta, see
navground::core::HLBehavior::get_eta(). Should be positive.
-
parameter hl.resolution int [Default:
101] # Resolution, see
navground::core::HLBehavior::get_resolution(). Should be positive.
-
parameter hl.tau float [Default:
0.125] # Tau, see
navground::core::HLBehavior::get_tau(). Should be positive.
ORCA behavior#
-
parameter orca.effective_center bool [Default:
false] # Whether to use an effective center, see
navground::core::ORCABehavior::is_using_effective_center().
-
parameter orca.time_horizon float [Default:
10.0] # Time horizon, see
navground::core::ORCABehavior::get_time_horizon(). Should be positive.
Other behaviors#
All properties of registered behavior are exposed as parameters
-
parameter <behavior_name>.<property_name> <property_type> [Default:
<default value of the property>] #
Controller#
-
parameter speed_tolerance float [Default:
0.05] # Speed below of which the agent is considered as stopped, see
navground::core::Controller::get_speed_tolerance(). Should be positive.
Vertical motion#
-
parameter altitude.enabled bool [Default:
false]# Whether to consider vertical information for state and control, see
navground::core::Controller3::is_limited_to_2d().
-
parameter altitude.optimal_speed float [Default:
0.1]# Optimal speed of the vertical motion, see
navground::core::Controller3::get_altitude_optimal_speed(). Should be positive.
-
parameter altitude.tau float [Default:
1.0] # Relaxation time of the vertical motion, see
navground::core::Controller3::get_altitude_tau(). Should be positive.
Subscriptions#
State#
- subscription odom nav_msgs/msg/Odometry#
Own odometry is used to set the behavior state, see
navground::core::Behavior::set_pose()andnavground::core::Behavior::set_twist().
- subscription neighbors navground_msgs/msg/Neighbors#
Dynamic Neighbors. Used by behaviors that have a
geometric environment state, seenavground::core::GeometricState::set_neighbors().
- subscription obstacles navground_msgs/msg/Obstacles#
Static obstacles. Used by behaviors that have a
geometric environment state, seenavground::core::GeometricState::set_static_obstacles().
Target#
- subscription target_point geometry_msgs/msg/PointStamped#
Set a target point. If an action is being executed, aborts it if is not following a point/pose, else updates the target.
- subscription target_pose geometry_msgs/msg/PoseStamped#
Set a target pose. If an action is being executed, aborts it if is not following a point/pose, else updates the target.
- subscription target_twist geometry_msgs/msg/TwistStamped#
Set a target twist. If an action is being executed, aborts it if is not following a twist, else updates the target.
- subscription stop std_msgs/msg/Empty#
Makes the agent stop. Aborts any action that is being executed.
Action Servers#
- action server go_to navground_msgs/action/GoToTarget#
Initiate an action towards a target pose or position, see
navground::core::Controller::go_to_position()andnavground::core::Controller::go_to_pose(). Ignores new requests if an action is already being executed.
Publishers#
- publisher cmd_vel geometry_msgs/msg/Twist#
Publishes the command returned by
navground::core::Controller3::update_3d(). Only published if publish_cmd_stamped is not set.
- publisher cmd_vel_stamped geometry_msgs/msg/TwistStamped#
Publishes the command returned by
navground::core::Controller3::update_3d(). Only published if publish_cmd_stamped is set.