BB integration for driving RC servos via pigpio on Raspberry Pi.
This library provides an actuator module for controlling RC servos directly connected to Raspberry Pi GPIO pins using the pigpio daemon.
Add bb_servo_pigpio to your list of dependencies in mix.exs:
def deps do
[
{:bb_servo_pigpio, "~> 0.4.0"}
]
end- Raspberry Pi with pigpio daemon running (
sudo pigpiod) - BB framework (
~> 0.2)
Define a joint with a servo actuator in your robot DSL:
defmodule MyRobot do
use BB
topology do
link :base do
joint :shoulder, type: :revolute do
limit lower: ~u(-45 degree), upper: ~u(45 degree), velocity: ~u(60 degree_per_second)
actuator :servo, {BB.Servo.Pigpio.Actuator, pin: 17}
sensor :feedback, {BB.Sensor.OpenLoopPositionEstimator, actuator: :servo}
link :arm do
# ...
end
end
end
end
endThe actuator automatically derives its configuration from the joint limits - no need to specify servo rotation range or speed separately.
Use the BB.Actuator module to send commands to servos. Three delivery methods
are available:
Commands are published via pubsub, enabling logging, replay, and multi-subscriber patterns:
# Send position command via pubsub
BB.Actuator.set_position(MyRobot, [:base, :shoulder, :servo], 0.5)
# With options
BB.Actuator.set_position(MyRobot, [:base, :shoulder, :servo], 0.5,
command_id: make_ref()
)Commands bypass pubsub for lower latency. Use when responsiveness matters more than observability:
# Fire-and-forget
BB.Actuator.set_position!(MyRobot, :servo, 0.5)Wait for the actuator to acknowledge the command:
case BB.Actuator.set_position_sync(MyRobot, :servo, 0.5) do
{:ok, :accepted} -> :ok
{:error, reason} -> handle_error(reason)
endBB.Servo.Pigpio.Actuator controls servo position via PWM.
Options:
| Option | Type | Default | Description |
|---|---|---|---|
pin |
integer | required | GPIO pin number |
min_pulse |
integer | 500 | Minimum PWM pulse width (microseconds) |
max_pulse |
integer | 2500 | Maximum PWM pulse width (microseconds) |
reverse? |
boolean | false | Reverse rotation direction |
update_speed |
unit | 50 Hz | PWM update frequency |
Behaviour:
- Maps joint position limits directly to PWM range
- Clamps commanded positions to joint limits
- Publishes
BB.Message.Actuator.BeginMotionafter each command - Calculates expected arrival time based on joint velocity limit
Use BB.Sensor.OpenLoopPositionEstimator from the BB core library for position
feedback. It subscribes to actuator BeginMotion messages and interpolates
position during movement.
sensor :feedback, {BB.Sensor.OpenLoopPositionEstimator, actuator: :servo}The actuator maps the joint's position limits to the servo's PWM range:
Joint lower limit -> min_pulse (500 microseconds)
Joint upper limit -> max_pulse (2500 microseconds)
Joint centre -> mid_pulse (1500 microseconds)
For a joint with limits -45 degrees to +45 degrees:
-45 degreesmaps to 500 microseconds0 degreesmaps to 1500 microseconds+45 degreesmaps to 2500 microseconds
Since RC servos don't provide position feedback, the open-loop position estimator estimates position based on commanded targets and expected arrival times:
- Actuator sends command and publishes
BeginMotionwith expected arrival time - Sensor receives
BeginMotionand interpolates position during movement - After arrival time, sensor reports the target position
This provides realistic position feedback for trajectory planning and monitoring.
When a position command is processed:
- Actuator clamps position to joint limits
- Converts angle to PWM pulse width
- Sends PWM command to pigpiod
- Publishes
BB.Message.Actuator.BeginMotionwith:initial_position- where the servo wastarget_position- where it's goingexpected_arrival- when it should arrive (monotonic milliseconds)command_id- correlation ID (if provided)command_type-:position
Full documentation is available at HexDocs.
