kompass.components.planner¶
Module Contents¶
Classes¶
Planner component config parameters |
|
Planner Component used for path planning during navigation. |
API¶
- class kompass.components.planner.PlannerConfig¶
Bases:
kompass.config.ComponentConfigPlanner component config parameters
- class kompass.components.planner.Planner(component_name: str, config_file: Optional[str] = None, config: Optional[kompass.components.planner.PlannerConfig] = None, inputs: Optional[Dict[str, kompass.components.ros.Topic]] = None, outputs: Optional[Dict[str, kompass.components.ros.Topic]] = None, **kwargs)¶
Bases:
kompass.components.component.ComponentPlanner Component used for path planning during navigation.
Input Topics:
map_layer: Global map used for planning.
Default:Topic(name="/map", msg_type="OccupancyGrid" qos_profile=QoSConfig(durability=qos.DurabilityPolicy.TRANSIENT_LOCAL))location: the robot current location.
DefaultTopic(name="/odom", msg_type="Odometry")goal_point: 2D navigation goal point on the map.
DefaultTopic(name="/goal", msg_type="PointStamped")
Outputs:
plan: Path to reach the goal point from start location.
DefaultTopic(name="/plan", msg_type="Path")reached_end: Flag indicating that the current planning target is reached
DefaultTopic(name="/reached_end", msg_type="Bool")
Available Run Types:
Set directly from Planner ‘run_type’ property.
TIMED: Compute a new plan periodically from current location (last message received on location input Topic) to the goal location (last message received on goal_point input Topic)
EVENT: Compute a new plan from current location on every new message received on goal_point input Topic
SERVER: Offers a PlanPath ROS service and computes a new plan on every service request
ACTIONSERVER: Offers a PlanPath ROS action and continuously computes a plan once an action request is received until goal point is reached
Usage Example:
from kompass.components import Planner, PlannerConfig from kompass.config import ComponentRunType from kompass_core.models import RobotType, Robot, LinearCtrlLimits, AngularCtrlLimits import numpy as np # Configure your robot my_robot = RobotConfig( model_type=RobotType.DIFFERENTIAL_DRIVE, geometry_type=RobotGeometry.Type.CYLINDER, geometry_params=np.array([0.1, 0.3]), ctrl_vx_limits=LinearCtrlLimits(max_vel=1.0, max_acc=1.5, max_decel=2.5), ctrl_omega_limits=AngularCtrlLimits( max_vel=1.0, max_acc=2.0, max_decel=2.0, max_steer=np.pi / 3 ), ) # Setup the planner config config = PlannerConfig( robot=my_robot, loop_rate=1.0 ) planner = Planner(component_name="planner", config=config) # Add rviz clicked_point as input topic planner.run_type = ComponentRunType.EVENT # Can also pass a string "Event" goal_topic = Topic(name="/clicked_point", msg_type="PoseStamped") planner.inputs(goal_point=goal_topic)
- config_from_file(config_file: str)¶
Configure the planner node and the algorithm from file
- Parameters:
config_file (str) – Path to config file (yaml, json, toml)
- init_variables()¶
Overwrites the init variables method called at Node init
- create_all_services()¶
Creates all node services
- destroy_all_services()¶
Destroys all node services
- trigger_main_action_server(goal_x: float = 0.0, goal_y: float = 0.0, goal_orientation: float = 0.0, tolerance_dist: float = 0.1, tolerance_ori: float = 0.1, algorithm_name: Optional[str] = None, **_) None¶
A component action to trigger the main planner action (Plan path to point until reached)
- Parameters:
goal_x (float, optional) – description, defaults to 0.0
goal_y (float, optional) – description, defaults to 0.0
tolerance_dist (float, optional) – description, defaults to 0.1
tolerance_ori (float, optional) – description, defaults to 0.1
algorithm_name (Optional[str], optional) – description, defaults to None
- main_service_callback(request: kompass_interfaces.srv.PlanPath.Request, response: kompass_interfaces.srv.PlanPath.Response)¶
Path planning service callback
- Parameters:
request (PlanPath.Request) – Path planning request containing goal location
response (PlanPath.Response) – Path planning response (success and plan)
- Returns:
Path planning response
- Return type:
PlanPath.Response
- reached_point(goal_point: kompass_core.models.RobotState, tolerance: kompass_interfaces.msg.PathTrackingError) bool¶
Checks if the current robot state is close to a given goal point
- Parameters:
goal_point (RobotState) – Goal point
tolerance (PathTrackingError) – Tolerance to goal
- Returns:
If the distance to the goal is less than the given tolerance
- Return type:
bool
- main_action_callback(goal_handle: kompass_interfaces.action.PlanPath.Goal)¶
Callback for the planner main action server
- Parameters:
goal_handle (PlanPathAction.Goal) – Incoming action goal
- Returns:
Action result
- Return type:
PlanPathAction.Result
- custom_on_configure()¶
- property robot: kompass.config.RobotConfig¶
- property run_type: kompass.config.ComponentRunType¶
- property inputs_keys: List[kompass.components.defaults.TopicsKeys]¶
- property outputs_keys: List[kompass.components.defaults.TopicsKeys]¶
- inputs(**kwargs)¶
- outputs(**kwargs)¶
- property odom_tf_listener: Optional[ros_sugar.tf.TFListener]¶
- property scan_tf_listener: ros_sugar.tf.TFListener¶
- property depth_tf_listener: ros_sugar.tf.TFListener¶
- property pc_tf_listener: ros_sugar.tf.TFListener¶
- get_transform_listener(src_frame: str, goal_frame: str) ros_sugar.tf.TFListener¶
- in_topic_name(key: Union[str, kompass.components.defaults.TopicsKeys]) Union[str, List[str], None]¶
- out_topic_name(key: Union[str, kompass.components.defaults.TopicsKeys]) Union[str, List[str], None]¶
- get_in_topic(key: Union[str, kompass.components.defaults.TopicsKeys]) Union[kompass.components.ros.Topic, List[kompass.components.ros.Topic], None]¶
- get_out_topic(key: Union[str, kompass.components.defaults.TopicsKeys]) Union[kompass.components.ros.Topic, List[kompass.components.ros.Topic], None]¶
- get_callback(key: Union[str, kompass.components.defaults.TopicsKeys], idx: int = 0) Optional[kompass.callbacks.GenericCallback]¶
- get_publisher(key: Union[str, kompass.components.defaults.TopicsKeys], idx: int = 0) ros_sugar.io.Publisher¶
- callbacks_inputs_check(inputs_to_check: Optional[List[str]] = None, inputs_to_exclude: Optional[List[str]] = None) bool¶