dynamic¶
Submodules¶
Classes¶
- class brom_drake.productions.motion_planning.offline.dynamic.chem_lab2.ChemLab2(time_step: float = 0.001, meshcat_port_number: int = 7001, plan_execution_speed: float = 0.2, pose_WorldBeaker: RigidTransform = None, table_length: float = 0.6, table_width: float = 2.0, table_height: float = 0.1, shelf_pose: RigidTransform = None, gripper_type: GripperType = GripperType.Robotiq_2f_85, **kwargs)[source]¶
Description
This production is the second in the chemistry lab series. It is used to test the motion planning capabilities of the robot in a chemistry lab setting with minimal constraints, but with full dynamics of the robot included in the simulation.
The earlier chemistry lab production (ChemLab1) ignored the physics of the arm and objects in order to simplify some calculations.
Parameters
- time_step: float, optional
The time step for the production, by default 1e-3.
- meshcat_port_number: int, optional
The port number for meshcat visualization, by default 7001.
- plan_execution_speed: float, optional
The speed at which to execute the motion plan, by default 0.2.
- pose_WorldBeaker: RigidTransform, optional
The pose of the beaker in the world frame, by default None.
- table_length: float, optional
The length of the table, by default 0.6.
- table_width: float, optional
The width of the table, by default 2.0.
- table_height: float, optional
The height of the table, by default 0.1.
- shelf_pose: RigidTransform, optional
The pose of the shelf in the world frame, by default None.
- gripper_type: GripperType, optional
The type of gripper to use, by default GripperType.Robotiq_2f_85.
Usage
To use this production, create an instance of the ChemLab2 class, provide it with a motion planning function, and then build it.
from brom_drake.motion_planning.algorithms.rrt.bidirectional_connect import ( BidirectionalRRTConnectPlanner, BidirectionalRRTConnectPlannerConfig, ) from brom_drake.productions import ChemLab2 # Create the production production = ChemLab2() # Create a planner object which will be used to plan the motion config = BidirectionalRRTConnectPlannerConfig( steering_step_size=0.2, ) planner2 = BidirectionalRRTConnectPlanner( production.arm, production.plant, production.scene_graph, config=config, ) # To build the production, we only need to provide a planning function # (can come from anywhere, not just a BaseRRTPlanner object) diagram, diagram_context = production.easy_cast_and_build( planner2.plan, with_watcher=True, ) print("Simulating...") # Simulate the diagram simulator = Simulator(diagram, diagram_context) simulator.set_target_realtime_rate(2.0) # Run simulation simulator.Initialize() simulator.AdvanceTo(0.05) planned_trajectory = production.plan_dispenser.planned_trajectory print(f"Expected end time of trajectory: {planned_trajectory.end_time()}") simulator.AdvanceTo(planned_trajectory.end_time()+2.0)
- add_beaker()[source]¶
Description
This method adds the beaker URDF to the production’s plant. The beaker’s URDF comes from the brom_drake robots directories.
- add_cast_and_build(cast: List[Tuple[Role, LeafSystem | Diagram]] = [], with_watcher: bool = False) Tuple[Diagram, Context][source]¶
Description
Modifies the normal add_cast_and_build, so that we share the context of the plant with the appropriate parts of the system.
TODO(kwesi): Consider making this a standard part of the OfflineDynamicMotionPlanningProduction class.
Parameters
- cast: List[Tuple[Role, Performer]], optional
The cast to add to the production, by default [].
- with_watcher: bool, optional
A Boolean that determines whether to add a watcher to the diagram, by default False.
Returns
- diagram: Diagram
The built diagram.
- diagram_context: Context
The context for the built diagram. This context will be used to initialize the watcher.
- add_motion_planning_components()[source]¶
Description
Add the following components to the production’s
builderin order to help with motion planning:plan_dispenser: An OpenLoopPlanDispenser which will describe the reference robot trajectory.
Connections between reference trajectory and UR10e station.
Gripper control components (type of control and an “open” command)
- add_shelf()[source]¶
Description
Add the shelf to the production’s plant. Welds the shelf to the world frame.
- add_supporting_cast()[source]¶
Description
This method adds all secondary cast members to the builder. The secondary cast members in the production are the:
Table, where the robot exists
Test Tube Holders
Component which share’s the robot model reference
Motion Planning components (e.g., dispensers, etc.)
Start and Goal sources
- add_table()[source]¶
Description
This method adds the table to the production’s plant. Welds the table to the world frame.
- add_test_tube_holders()[source]¶
Description
This method adds the test tube holders to the production’s plant. Welds the test tube holders to the world frame with using predefined poses.
- configure_collision_filter(scene_graph_context: Context)[source]¶
Description
This method configures the collision filter in the scene graph so that we ignore: - Self collisions of the shelf - Collisions between adjacent robot links (TODO)
Parameters
- scene_graph_context: Context
The context for the scene graph.
- define_pose_ik_problem(pose_WorldTarget: RigidTransform, target_frame_name: str, eps0: float = 0.025, orientation_cost_scaling: float = 0.25) InverseKinematics[source]¶
Description
Sets up the inverse kinematics problem for the start pose input to theis function. :return:
- easy_cast_and_build(planning_algorithm: Callable[[ndarray, ndarray, Callable[[ndarray], bool]], Tuple[DiGraph | ndarray, bool]], with_watcher: bool = False) Tuple[Diagram, Context][source]¶
Description
This function is used to easily cast and build the production.
Parameters
- planning_algorithm: Callable[[np.ndarray, np.ndarray, Callable[[np.ndarray], bool]],Tuple[MotionPlan, bool]]
The algorithm that we will use to plan the motion.
- with_watcher: A Boolean that determines whether to add a watcher to the diagram.
by default False.
Returns
- diagram: Diagram
The built diagram.
- diagram_context: Context
The context for the built diagram. If with_watcher is True, this context will be used to initialize the watcher.
- property goal_configuration: ndarray¶
Description
Get the goal pose.
Returns
- q_goal: np.ndarray
The goal configuration of the robot.
- property goal_pose: RigidTransform¶
Description
Get the goal pose of the end effector frame.
Returns
- pose_WorldGoal: RigidTransform
The goal pose of the end effector frame.
- property id: ProductionID¶
Description
Always returns the ProductionID for ChemLab2.
Returns
- ProductionID.kChemLab2: ProductionID
The ProductionID for ChemLab2.
- initialize_pose_data()[source]¶
Description
Initialize the following poses if they are not already set:
pose_WorldShelf
pose_WorldBeaker
pose_WorldHolder
pose_BeakerGoal
pose_HolderStart
- solve_forward_kinematics_problem_for_arm(robot_joint_positions: ndarray) RigidTransform[source]¶
Description
This method solves the forward kinematics problem for the UR10e arm by itself.
- property start_configuration¶
Description
Get the start configuration of the robot in the production.
Returns
- q_start: np.ndarray
The start configuration of the robot.
- property start_pose: RigidTransform¶
Description
Get the start pose. This should be defined by the subclass.
Returns
- pose_WorldStart: RigidTransform
The start pose of the end effector frame.
Functions¶
(None found)
Variables¶
- brom_drake.productions.motion_planning.offline.dynamic.chem_lab2.DEFAULT_BROM_MODELS_DIR = './brom/models'¶
str(object=’’) -> str str(bytes_or_buffer[, encoding[, errors]]) -> str
Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.__str__() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to ‘strict’.