systems¶
Submodules¶
Classes¶
- class brom_drake.motion_planning.systems.prototypical_planner.PrototypicalPlannerSystem(plant: MultibodyPlant, scene_graph: SceneGraph, planning_algorithm: Callable[[ndarray, ndarray, Callable[[ndarray], bool]], Tuple[DiGraph | ndarray, int]], robot_model_idx: ModelInstanceIndex = None, **kwargs)[source]¶
Description¶
This function is meant to be a prototypical planner system. It will receive a planning algorithm and wrap that algorithm in a LeafSystem that works in Brom.
- GetPlanIsReady(context, output: AbstractValue)[source]¶
- Description:
This function checks if the plan is ready.
- check_collision_in_config(q_model: ndarray) bool[source]¶
Description¶
This function checks for collisions in the robot’s environment.
Arguments¶
- q_modelnp.ndarray
The model configuration that we are checking for collisions.
- compute_plan_if_not_available(context: Context, output: AbstractValue)[source]¶
Description¶
This function computes the plan if it is not available.
Arguments¶
- contextContext
The context that we are working with.
- outputAbstractValue
The output that will be produced by the output port
- create_input_ports()[source]¶
- Description:
This function creates the input ports for the RRT planner.
- create_output_ports()[source]¶
- Description:
This function creates the output ports for the RRT planner.
- define_pose_ik_problem(input_pose_vec: ndarray, eps0: float = 0.025) InverseKinematics[source]¶
Description¶
Sets up the inverse kinematics problem for the start pose input to theis function. :return:
- class brom_drake.motion_planning.systems.rrt_plan_generator.RRTPlanGenerator(plant: MultibodyPlant, scene_graph: SceneGraph, robot_model_idx: ModelInstanceIndex = None, rrt_config: BaseRRTPlannerConfig = None, dim_config: int = None)[source]¶
Description
This class will call the RRT planning algorithm for and then share it in an output port.
Parameters
- plant: MultibodyPlant
The multibody plant containing the robot and environment.
- scene_graph: SceneGraph
The scene graph associated with the multibody plant.
- robot_model_idx: ModelInstanceIndex
The model instance index of the robot to be planned for.
- rrt_config: BaseRRTPlannerConfig
The configuration for the RRT planner.
- dim_config: int
The dimension of the configuration space.
- GetPlanIsReady(context, output: AbstractValue)[source]¶
Description
This function checks if the plan is ready.
- compute_plan_if_not_available(context, output: AbstractValue)[source]¶
Description
This function computes the plan if it is not available.
- create_input_ports()[source]¶
Description
This function creates the input ports for the RRT planner.
- create_output_ports()[source]¶
Description
This function creates the output ports for the RRT planner.
- define_pose_ik_problem(input_pose_vec: ndarray, eps0: float = 0.025) InverseKinematics[source]¶
Description
Sets up the inverse kinematics problem for the start pose input to this function.
Parameters
- input_pose_vec: np.ndarray
The desired end-effector pose as a 7D vector (x, y, z, qx, qy, qz, qw).
- eps0: float, optional
The position tolerance for the IK problem. By default, this is set to 2.5 cm.
Returns
- ik_problem: InverseKinematics
The defined inverse kinematics problem.
- property n_actuated_dof: int¶
Description
This method uses the plant and the robot model idx to identify the number of degrees of freedom we have for control. :return:
Functions¶
(None found)
Variables¶
(None found)