Simulation Physics

pyfrc supports simplistic custom physics model implementations for simulation and testing support. It can be as simple or complex as you want to make it. We will continue to add helper functions (such as the pyfrc.physics.drivetrains module) to make this a lot easier to do. General purpose physics implementations are welcome also!

The idea is you provide a PhysicsEngine object that interacts with the simulated HAL, and modifies motors/sensors accordingly depending on the state of the simulation. An example of this would be measuring a motor moving for a set period of time, and then changing a limit switch to turn on after that period of time. This can help you do more complex simulations of your robot code without too much extra effort.

Note

One limitation to be aware of is that the physics implementation currently assumes that you are only calling wpilib.delay() once per main loop iteration. If you do it more than that, you may get some rather funky results.

By default, pyfrc doesn’t modify any of your inputs/outputs without being told to do so by your code or the simulation GUI.

See the physics sample for more details.

Enabling physics support

You must create a python module called physics.py next to your robot.py. A physics module must have a class called PhysicsEngine which must have a function called update_sim. When initialized, it will be passed an instance of this object.

You must also create a ‘sim’ directory, and place a config.json file there, with the following JSON information:

{
  "pyfrc": {
    "robot": {
      "w": 2,
      "h": 3,
      "starting_x": 2,
      "starting_y": 20,
      "starting_angle": 0
    }
  }
}
class pyfrc.physics.core.PhysicsEngine(physics_controller)[source]

Your physics module must contain a class called PhysicsEngine, and it must implement the same functions as this class.

Alternatively, you can inherit from this object. However, that is not required.

The constructor must take the following arguments:

Parameters:physics_controller (PhysicsInterface) – The physics controller interface
initialize(hal_data)[source]

Called with the hal_data dictionary before the robot has started running. Some values may be overwritten when devices are initialized… it’s not consistent yet, sorry.

update_sim(hal_data, now, tm_diff)[source]

Called when the simulation parameters for the program need to be updated. This is mostly when wpilib.delay() is called.

Parameters:
  • hal_data – A giant dictionary that has all data about the robot. See hal-sim/hal_impl/data.py in robotpy-wpilib’s repository for more information on the contents of this dictionary.
  • now (float) – The current time
  • tm_diff (float) – The amount of time that has passed since the last time that this function was called
exception pyfrc.physics.core.PhysicsInitException[source]
class pyfrc.physics.core.PhysicsInterface(robot_path, fake_time, config_obj)[source]

An instance of this is passed to the constructor of your PhysicsEngine object. This instance is used to communicate information to the simulation, such as moving the robot on the field displayed to the user.

add_analog_gyro_channel(ch)[source]

This function is no longer needed

add_device_gyro_channel(angle_key)[source]
Parameters:angle_key – The name of the angle key in hal_data['robot']
add_gyro_channel(ch)

This function is no longer needed

drive(speed, rotation_speed, tm_diff)[source]

Call this from your PhysicsEngine.update_sim() function. Will update the robot’s position on the simulation field.

You can either calculate the speed & rotation manually, or you can use the predefined functions in pyfrc.physics.drivetrains.

The outputs of the drivetrains.* functions should be passed to this function.

Note

The simulator currently only allows 2D motion

Parameters:
  • speed – Speed of robot in ft/s
  • rotation_speed – Clockwise rotational speed in radians/s
  • tm_diff – Amount of time speed was traveled (this is the same value that was passed to update_sim)
get_offset(x, y)[source]

Computes how far away and at what angle a coordinate is located.

Distance is returned in feet, angle is returned in degrees

Returns:distance,angle offset of the given x,y coordinate

New in version 2018.1.7.

get_position()[source]
Returns:Robot’s current position on the field as (x,y,angle). x and y are specified in feet, angle is in radians
vector_drive(vx, vy, vw, tm_diff)[source]

Call this from your PhysicsEngine.update_sim() function. Will update the robot’s position on the simulation field.

This moves the robot using a vector relative to the robot instead of by speed/rotation speed.

Parameters:
  • vx – Speed in x direction relative to robot in ft/s
  • vy – Speed in y direction relative to robot in ft/s
  • vw – Clockwise rotational speed in rad/s
  • tm_diff – Amount of time speed was traveled

Drivetrain support

Based on input from various drive motors, these helper functions simulate moving the robot in various ways. Many thanks to Ether for assistance with the motion equations.

When specifying the robot speed to the below functions, the following may help you determine the approximate speed of your robot:

  • Slow: 4ft/s
  • Typical: 5 to 7ft/s
  • Fast: 8 to 12ft/s

Obviously, to get the best simulation results, you should try to estimate the speed of your robot accurately.

Here’s an example usage of the drivetrains:

from pyfrc.physics import drivetrains

class PhysicsEngine:
    
    def __init__(self, physics_controller):
        self.physics_controller = physics_controller
        self.drivetrain = drivetrains.TwoMotorDrivetrain(deadzone=drivetrains.linear_deadzone(0.2))
        
    def update_sim(self, hal_data, now, tm_diff):
        # TODO: get motor values from hal_data
        speed, rotation = self.drivetrain.get_vector(l_motor, r_motor)
        self.physics_controller.drive(speed, rotation, tm_diff)
        
        # optional: compute encoder
        # l_encoder = self.drivetrain.l_speed * tm_diff
class pyfrc.physics.drivetrains.FourMotorDrivetrain(x_wheelbase=2, speed=5, deadzone=None)[source]

Four motors, each side chained together. The motion equations are as follows:

FWD = (L+R)/2
RCW = (L-R)/W
  • L is forward speed of the left wheel(s), all in sync
  • R is forward speed of the right wheel(s), all in sync
  • W is wheelbase in feet

If you called “SetInvertedMotor” on any of your motors in RobotDrive, then you will need to multiply that motor’s value by -1.

Note

WPILib RobotDrive assumes that to make the robot go forward, the left motors must be set to -1, and the right to +1

New in version 2018.2.0.

Parameters:
  • x_wheelbase (float) – The distance in feet between right and left wheels.
  • speed (float) – Speed of robot in feet per second (see above)
  • deadzone (Optional[Callable[[float], float]]) – A function that adjusts the output of the motor (see linear_deadzone())
get_vector(lr_motor, rr_motor, lf_motor, rf_motor)[source]
Parameters:
  • lr_motor (float) – Left rear motor value (-1 to 1); -1 is forward
  • rr_motor (float) – Right rear motor value (-1 to 1); 1 is forward
  • lf_motor (float) – Left front motor value (-1 to 1); -1 is forward
  • rf_motor (float) – Right front motor value (-1 to 1); 1 is forward
Return type:

Tuple[float, float]

Returns:

speed of robot (ft/s), clockwise rotation of robot (radians/s)

l_speed = 0

Use this to compute encoder data after get_vector is called

class pyfrc.physics.drivetrains.MecanumDrivetrain(x_wheelbase=2, y_wheelbase=3, speed=5, deadzone=None)[source]

Four motors, each with a mechanum wheel attached to it.

If you called “SetInvertedMotor” on any of your motors in RobotDrive, then you will need to multiply that motor’s value by -1.

Note

WPILib RobotDrive assumes that to make the robot go forward, all motors are set to +1

New in version 2018.2.0.

Parameters:
  • x_wheelbase (float) – The distance in feet between right and left wheels.
  • y_wheelbase (float) – The distance in feet between forward and rear wheels.
  • speed (float) – Speed of robot in feet per second (see above)
  • deadzone (Optional[Callable[[float], float]]) – A function that adjusts the output of the motor (see linear_deadzone())
get_vector(lr_motor, rr_motor, lf_motor, rf_motor)[source]

Given motor values, retrieves the vector of (distance, speed) for your robot

Parameters:
  • lr_motor (float) – Left rear motor value (-1 to 1); 1 is forward
  • rr_motor (float) – Right rear motor value (-1 to 1); 1 is forward
  • lf_motor (float) – Left front motor value (-1 to 1); 1 is forward
  • rf_motor (float) – Right front motor value (-1 to 1); 1 is forward
Return type:

Tuple[float, float, float]

Returns:

Speed of robot in x (ft/s), Speed of robot in y (ft/s), clockwise rotation of robot (radians/s)

lr_speed = 0

Use this to compute encoder data after get_vector is called

class pyfrc.physics.drivetrains.TwoMotorDrivetrain(x_wheelbase=2, speed=5, deadzone=None)[source]

Two center-mounted motors with a simple drivetrain. The motion equations are as follows:

FWD = (L+R)/2
RCW = (L-R)/W
  • L is forward speed of the left wheel(s), all in sync
  • R is forward speed of the right wheel(s), all in sync
  • W is wheelbase in feet

If you called “SetInvertedMotor” on any of your motors in RobotDrive, then you will need to multiply that motor’s value by -1.

Note

WPILib RobotDrive assumes that to make the robot go forward, the left motor must be set to -1, and the right to +1

New in version 2018.2.0.

Parameters:
  • x_wheelbase (float) – The distance in feet between right and left wheels.
  • speed (float) – Speed of robot in feet per second (see above)
  • deadzone (Optional[Callable[[float], float]]) – A function that adjusts the output of the motor (see linear_deadzone())
get_vector(l_motor, r_motor)[source]

Given motor values, retrieves the vector of (distance, speed) for your robot

Parameters:
  • l_motor (float) – Left motor value (-1 to 1); -1 is forward
  • r_motor (float) – Right motor value (-1 to 1); 1 is forward
Return type:

Tuple[float, float]

Returns:

speed of robot (ft/s), clockwise rotation of robot (radians/s)

pyfrc.physics.drivetrains.four_motor_drivetrain(lr_motor, rr_motor, lf_motor, rf_motor, x_wheelbase=2, speed=5, deadzone=None)[source]

Deprecated since version 2018.2.0: Use FourMotorDrivetrain instead

pyfrc.physics.drivetrains.four_motor_swerve_drivetrain(lr_motor, rr_motor, lf_motor, rf_motor, lr_angle, rr_angle, lf_angle, rf_angle, x_wheelbase=2, y_wheelbase=2, speed=5, deadzone=None)[source]

Four motors that can be rotated in any direction

If any motors are inverted, then you will need to multiply that motor’s value by -1.

Parameters:
  • lr_motor – Left rear motor value (-1 to 1); 1 is forward
  • rr_motor – Right rear motor value (-1 to 1); 1 is forward
  • lf_motor – Left front motor value (-1 to 1); 1 is forward
  • rf_motor – Right front motor value (-1 to 1); 1 is forward
  • lr_angle – Left rear motor angle in degrees (0 to 360 measured clockwise from forward position)
  • rr_angle – Right rear motor angle in degrees (0 to 360 measured clockwise from forward position)
  • lf_angle – Left front motor angle in degrees (0 to 360 measured clockwise from forward position)
  • rf_angle – Right front motor angle in degrees (0 to 360 measured clockwise from forward position)
  • x_wheelbase – The distance in feet between right and left wheels.
  • y_wheelbase – The distance in feet between forward and rear wheels.
  • speed – Speed of robot in feet per second (see above)
  • deadzone – A function that adjusts the output of the motor (see linear_deadzone())
Returns:

Speed of robot in x (ft/s), Speed of robot in y (ft/s), clockwise rotation of robot (radians/s)

pyfrc.physics.drivetrains.linear_deadzone(deadzone)[source]

Real motors won’t actually move unless you give them some minimum amount of input. This computes an output speed for a motor and causes it to ‘not move’ if the input isn’t high enough. Additionally, the output is adjusted linearly to compensate.

Example: For a deadzone of 0.2:

  • Input of 0.0 will result in 0.0
  • Input of 0.2 will result in 0.0
  • Input of 0.3 will result in ~0.12
  • Input of 1.0 will result in 1.0

This returns a function that computes the deadzone. You should pass the returned function to one of the drivetrain simulation functions as the deadzone parameter.

Parameters:
  • motor_input – The motor input (between -1 and 1)
  • deadzone (float) – Minimum input required for the motor to move (between 0 and 1)
Return type:

Callable[[float], float]

pyfrc.physics.drivetrains.mecanum_drivetrain(lr_motor, rr_motor, lf_motor, rf_motor, x_wheelbase=2, y_wheelbase=3, speed=5, deadzone=None)[source]

Deprecated since version 2018.2.0: Use MecanumDrivetrain instead

pyfrc.physics.drivetrains.two_motor_drivetrain(l_motor, r_motor, x_wheelbase=2, speed=5, deadzone=None)[source]

Deprecated since version 2018.2.0: Use TwoMotorDrivetrain instead

Motion support

class pyfrc.physics.motion.LinearMotion(name, motor_ft_per_sec, ticks_per_feet, max_position=None, min_position=0)[source]

Helper for simulating motion involving a encoder directly coupled to a motor.

Here’s an example that shows a linear motion of 6ft at 2 ft/s with a 360-count-per-ft encoder, coupled to a PWM motor on port 0 and the first encoder object:

from pyfrc.physics import motion

class PhysicsEngine:
    
    def __init__(self, physics_controller):
        self.motion = pyfrc.physics.motion.LinearMotion('Motion', 2, 360, 6)
    
    def update_sim(self, hal_data, now, tm_diff):
        
        motor_value = hal_data['pwm'][0]['value']
        hal_data['encoder'][0]['value'] = self.motion.compute(motor_value)

New in version 2018.3.0.

Parameters:
  • name (str) – Name of motion, shown in pyfrc simulation UI
  • motor_ft_per_sec (float) – Motor travel in feet per second (or whatever units you want)
  • ticks_per_feet (int) – Number of encoder ticks per feet
  • max_position (Optional[float]) – Maximum position that this motion travels to
  • min_position (Optional[float]) – Minimum position that this motion travels to
position_ft = 0

Current computed position of motion, in feet

position_ticks = 0

Current computed position of motion (encoder ticks)

Custom labels

If you write data to the ‘custom’ key of the hal_data dictionary, the data will be shown on the pyfrc simulation UI. The key will be the label for the data, and the value will be rendered as text inside the box:

# first time you set the data
hal_data.setdefault('custom', {})['My Label'] = '---'

# All other times
hal_data['custom']['My Label'] = 1

New in version 2018.3.0.

Custom drawing

pyfrc.sim.get_user_renderer()[source]

This retrieves an object that can be used to draw on the simulated field when running the robot in simulation.

Returns:None if no renderers are available, else a UserRenderer object
class pyfrc.sim.field.user_renderer.UserRenderer[source]
draw_line(line_pts, color='#ff0000', robot_coordinates=False, relative_to_first=False, arrow=True, scale=(1, 1), **kwargs)[source]
Parameters:
  • line_pts – A list of (x,y) pairs to draw. (x,y) are in field units which are measured in feet
  • color – The color of the line, expressed as a 6-digit hex color
  • robot_coordinates – If True, the pts will be adjusted such that the first point starts at the center of the robot and that x and y coordinates are rotated according to the robot’s current heading. If a tuple, then the pts are adjusted relative to the robot center AND the x,y in the tuple
  • relative_to_first – If True, the points will be adjusted such that the first point is considered to be (0,0)
  • arrow – If True, draw the line with an arrow at the end
  • scale – Multiply all points by this (x,y) tuple
  • kwargs – Keyword options to pass to tkinter.create_line
draw_pathfinder_trajectory(trajectory, color='#ff0000', offset=None, scale=(1, 1), show_dt=False, dt_offset=0.0, **kwargs)[source]

Special helper function for drawing trajectories generated by robotpy-pathfinder

Parameters:
  • trajectory – A list of pathfinder segment objects
  • offset – If specified, should be x/y tuple to add to the path relative to the robot coordinates
  • scale – Multiply all points by this (x,y) tuple
  • show_dt – draw text every N seconds along path, or False
  • dt_offset – add this to each dt shown
  • kwargs – Keyword options to pass to tkinter.create_line
draw_text(text, pt, color='#000000', fontSize=10, robot_coordinates=False, scale=(1, 1), **kwargs)[source]
Parameters:
  • text – Text to render
  • pt – A tuple of (x,y) in field units (which are measured in feet)
  • color – The color of the text, expressed as a 6-digit hex color
  • robot_coordinates – If True, the pt will be adjusted such that the point starts at the center of the robot and that x and y coordinates are rotated according to the robot’s current heading. If a tuple, then the pt is adjusted relative to the robot center AND the x,y in the tuple
  • arrow – If True, draw the line with an arrow at the end
  • scale – Multiply all points by this (x,y) tuple
  • kwargs – Keyword options to pass to tkinter.create_text

Camera ‘simulator’

The ‘vision simulator’ provides objects that assist in modeling inputs from a camera processing system.

class pyfrc.physics.visionsim.VisionSim(targets, camera_fov, view_dst_start, view_dst_end, data_frequency=15, data_lag=0.05, physics_controller=None)[source]

This helper object is designed to help you simulate input from a vision system. The algorithm is a very simple approximation and has some weaknesses, but it should be a good start and general enough to work for many different usages.

There are a few assumptions that this makes:

  • Your camera code sends new data at a constant frequency
  • The data from the camera lags behind at a fixed latency
  • If the camera is too close, the target cannot be seen
  • If the camera is too far, the target cannot be seen
  • You can only ‘see’ the target when the ‘front’ of the robot is around particular angles to the target
  • The camera is in the center of your robot (this simplifies some things, maybe fix this in the future…)

To use this, create an instance in your physics simulator:

targets = [
    VisionSim.Target(...)
]

Then call the compute() method from your update_sim method whenever your camera processing is enabled:

# in physics engine update_sim()
x, y, angle = self.physics_controller.get_position()

if self.camera_enabled:
    data = self.vision_sim.compute(now, x, y, angle)
    if data is not None:
        self.nt.putNumberArray('/camera/target', data[0])
else:
    self.vision_sim.dont_compute()

Note

There is a working example in the examples repository you can use to try this functionality out

There are a lot of constructor parameters:

Parameters:
  • targets – List of target positions (x, y) on field in feet
  • view_angle_start – Center angle that the robot can ‘see’ the target from (in degrees)
  • camera_fov – Field of view of camera (in degrees)
  • view_dst_start – If the robot is closer than this, the target cannot be seen
  • view_dst_end – If the robot is farther than this, the target cannot be seen
  • data_frequency – How often the camera transmits new coordinates
  • data_lag – How long it takes for the camera data to be processed and make it to the robot
  • physics_controller – If set, will draw target information in UI
Target

alias of VisionSimTarget

compute(now, x, y, angle)[source]

Call this when vision processing should be enabled

Parameters:
  • now – The value passed to update_sim
  • x – Returned from physics_controller.get_position
  • y – Returned from physics_controller.get_position
  • angle – Returned from physics_controller.get_position
Returns:

None or list of tuples of (found=0 or 1, capture_time, offset_degrees, distance). The tuples are ordered by absolute offset from the target. If a list is returned, it is guaranteed to have at least one element in it.

Note: If your vision targeting doesn’t have the ability to focus on multiple targets, then you should ignore the other elements.

dont_compute()[source]

Call this when vision processing should be disabled

get_immediate_distance()[source]

Use this data to feed to a sensor that is mostly instantaneous (such as an ultrasonic sensor).

Note

You must call compute() first.

class pyfrc.physics.visionsim.VisionSimTarget(x, y, view_angle_start, view_angle_end)[source]

Target object that you pass the to the constructor of VisionSim

Parameters:
  • x – Target x position
  • y – Target y position
  • view_angle_start
  • view_angle_end – clockwise from start angle

View angle is defined in degrees from 0 to 360, with 0 = east, increasing clockwise. So, if the robot could only see the target from the south east side, you would use a view angle of start=0, end=90.