Double Pendulum Numerical Models¶
The rcp.doublependulum module contains several classes to support numerical simulation
and control of a double pendulum system. Graphical rendering is handled separately in
rcp.QtDoublePendulum
.
rcp.doublependulum¶
- class rcp.doublependulum.DoublePendulumController[source]¶
Prototype for a double-pendulum controller. This class is typically subclassed to customize the control strategy and the subclass passed into the common application framework.
- Variables:
initial_state – four-element numpy array used to initialize the simulator state: [q1, q2, qd1, qd2]
kp – two-element numpy array with default proportional position gains
ki – two-element numpy array with default integral gains
kd – two-element numpy array with default velocity damping gain
identity – zero-based serial number identifying the instance in the case of multiple simulations
- apply_configuration(config)[source]¶
Hook for applying parameters saved in a configuration file. The default implementation does nothing.
- Parameters:
config – configparser object (which implements the mapping protocol)
- compute_control(t, dt, state, tau)[source]¶
Method called from numerical pendulum simulation to calculate the next step of applied torques. This is usually overridden in a subclass, but the default implementation applies a fixed-target PD position control.
- Parameters:
t – time in seconds since simulation began
state – four element ndarray of joint positions q and joint velocities qd as [q1, q2, qd1, qd2], expressed in radians and radians/sec
tau – two element ndarray to fill in with joint torques to apply
- connect_console(console)[source]¶
Attach a console object to be used for debugging output. The object needs to implement write().
- gather_configuration(config)[source]¶
Hook for saving parameters in a configuration file. The default implementation does nothing.
- Parameters:
config – configparser object (which implements the mapping protocol)
- set_identity(serial_number)[source]¶
Set the specific identification number for this controller out of multiples.
- set_world(world)[source]¶
Set the ‘world’ object which can answer global information queries. This is a deliberately abstract interface between sub-classes and the application framework.
- setup()[source]¶
Hook for final one-time object configuration. This is called once prior to the start of the simulation. The default implementation does nothing.
- class rcp.doublependulum.DoublePendulumSimulator[source]¶
Numerical dynamic simulation of a frictionless double pendulum. It communicates with a user-supplied control object to compute applied joint torques.
- Variables:
t – simulated time in seconds
state – four-element vector of dynamic state [q1 q2 qd1 qd2] (position and velocity)
origin – two-element vector locating the pendulum base in world coordinates
- connect_controller(controller)[source]¶
Attach a controller object used to compute joint torques and set the initial state.
- deriv()[source]¶
Calculate the accelerations for a rigid body double-pendulum dynamics model.
- Returns:
system derivative vector as a numpy ndarray
- endpointIK(target)[source]¶
Compute two inverse kinematics solutions for a target end position. The target is a Cartesian position vector (two-element ndarray) in world coordinates, and the result vectors are joint angles as ndarrays [q0, q1]. If the target is out of reach, returns the closest pose.
- forwardKinematics(q)[source]¶
Compute the forward kinematics. Returns the world-coordinate Cartesian position of the elbow and endpoint for a given joint angle vector.
- param q:
two-element list or ndarray with [q1, q2] joint angles
- return:
tuple (elbow, end) of two-element ndarrays with [x,y] locations