1
0
mirror of https://github.com/hybridgroup/gobot.git synced 2025-04-24 13:48:49 +08:00

Add Jetson Nano adpator

This commit is contained in:
Thomas Kohler 2022-10-23 12:07:09 +02:00 committed by GitHub
commit b3a3564869
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
9 changed files with 913 additions and 0 deletions

View File

@ -0,0 +1,33 @@
// +build example
//
// Do not build by default.
package main
import (
"time"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/gpio"
"gobot.io/x/gobot/platforms/jetson"
)
func main() {
r := jetson.NewAdaptor()
led := gpio.NewLedDriver(r, "40")
work := func() {
gobot.Every(1*time.Second, func() {
led.Toggle()
})
}
robot := gobot.NewRobot("blinkBot",
[]gobot.Connection{r},
[]gobot.Device{led},
work,
)
robot.Start()
}

View File

@ -0,0 +1,56 @@
// +build example
//
// Do not build by default.
package main
//
// before to run
// 1. check Jetson io pwm pin configure `sudo /opt/nvidia/jetson-io/jetson-io.py`
// 2. if end pin configure, reboot Jetson nano.
// 3. run gobot
import (
"log"
"time"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/gpio"
"gobot.io/x/gobot/platforms/jetson"
)
func main() {
jetsonAdaptor := jetson.NewAdaptor()
servo := gpio.NewServoDriver(jetsonAdaptor, "32")
counter := 0
flg := true
work := func() {
gobot.Every(100*time.Millisecond, func() {
log.Println("Turning", counter)
servo.Move(uint8(counter))
if counter == 140 {
flg = false
} else if counter == 30 {
flg = true
}
if flg {
counter = counter + 1
} else {
counter = counter - 1
}
})
}
robot := gobot.NewRobot("Jetsonservo",
[]gobot.Connection{jetsonAdaptor},
[]gobot.Device{servo},
work,
)
robot.Start()
}

View File

@ -0,0 +1,64 @@
# Jetson Nano
The Jetson Nano is ARM based single board computer with digital & PWM GPIO, and i2c interfaces built in.
The Gobot adaptor for the Jetson Nano should support Jetno Nano.
For more info about the Jetson Nano platform, click [here](https://developer.nvidia.com/embedded/jetson-nano/).
## How to Install
We recommend updating to the latest jetson-nano OS when using the Jetson Nano, however Gobot should also support older versions of the OS, should your application require this.
You would normally install Go and Gobot on your workstation. Once installed, cross compile your program on your workstation, transfer the final executable to your Jetson Nano, and run the program on the Jetson Nano as documented here.
```
go get -d -u gobot.io/x/gobot/...
```
## How to Use
The pin numbering used by your Gobot program should match the way your board is labeled right on the board itself.
```go
package main
import (
"time"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/gpio"
"gobot.io/x/gobot/platforms/jetson"
)
func main() {
r := jetson.NewAdaptor()
led := gpio.NewLedDriver(r, "40")
work := func() {
gobot.Every(1*time.Second, func() {
led.Toggle()
})
}
robot := gobot.NewRobot("blinkBot",
[]gobot.Connection{r},
[]gobot.Device{led},
work,
)
robot.Start()
}
```
## How to Connect
### Compiling
Once you have compiled your code, you can upload your program and execute it on the Jetson Nano from your workstation using the `scp` and `ssh` commands like this:
```bash
$ scp jetson-nano_blink jn@192.168.1.xxx:/home/jn/
$ ssh -t jn@192.168.1.xxx "./jetson-nano_blink"
```

7
platforms/jetson/doc.go Normal file
View File

@ -0,0 +1,7 @@
/*
Package Jetson contains the Gobot adaptor for the Jetson Nano.
For further information refer to Jetson README:
https://github.com/hybridgroup/gobot/blob/master/platforms/jetson/README.md
*/
package jetson // import "gobot.io/x/gobot/platforms/jetson"

View File

@ -0,0 +1,290 @@
package jetson
import (
"errors"
"fmt"
"sync"
multierror "github.com/hashicorp/go-multierror"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/drivers/spi"
"gobot.io/x/gobot/sysfs"
)
const pwmDefaultPeriod = 3000000
// Adaptor is the Gobot Adaptor for the Jetson Nano
type Adaptor struct {
mutex *sync.Mutex
name string
revision string
digitalPins map[int]*sysfs.DigitalPin
pwmPins map[int]*PWMPin
i2cDefaultBus int
i2cBuses [2]i2c.I2cDevice
spiDefaultBus int
spiDefaultChip int
spiDevices [2]spi.Connection
spiDefaultMode int
spiDefaultMaxSpeed int64
}
// NewAdaptor creates a Raspi Adaptor
func NewAdaptor() *Adaptor {
j := &Adaptor{
mutex: &sync.Mutex{},
name: gobot.DefaultName("JetsonNano"),
digitalPins: make(map[int]*sysfs.DigitalPin),
pwmPins: make(map[int]*PWMPin),
}
j.i2cDefaultBus = 1
j.spiDefaultBus = 0
j.spiDefaultChip = 0
j.spiDefaultMode = 0
j.spiDefaultMaxSpeed = 10000000
return j
}
// Name returns the Adaptor's name
func (j *Adaptor) Name() string {
j.mutex.Lock()
defer j.mutex.Unlock()
return j.name
}
// SetName sets the Adaptor's name
func (j *Adaptor) SetName(n string) {
j.mutex.Lock()
defer j.mutex.Unlock()
j.name = n
}
// Connect starts connection with board and creates
// digitalPins and pwmPins adaptor maps
func (j *Adaptor) Connect() (err error) {
return
}
// Finalize closes connection to board and pins
func (j *Adaptor) Finalize() (err error) {
j.mutex.Lock()
defer j.mutex.Unlock()
for _, pin := range j.digitalPins {
if pin != nil {
if perr := pin.Unexport(); err != nil {
err = multierror.Append(err, perr)
}
}
}
for _, pin := range j.pwmPins {
if pin != nil {
if perr := pin.Unexport(); err != nil {
err = multierror.Append(err, perr)
}
}
}
for _, bus := range j.i2cBuses {
if bus != nil {
if e := bus.Close(); e != nil {
err = multierror.Append(err, e)
}
}
}
for _, dev := range j.spiDevices {
if dev != nil {
if e := dev.Close(); e != nil {
err = multierror.Append(err, e)
}
}
}
return
}
// DigitalPin returns matched digitalPin for specified values
func (j *Adaptor) DigitalPin(pin string, dir string) (sysfsPin sysfs.DigitalPinner, err error) {
i, err := j.translatePin(pin)
if err != nil {
return
}
currentPin, err := j.getExportedDigitalPin(i, dir)
if err != nil {
return
}
if err = currentPin.Direction(dir); err != nil {
return
}
return currentPin, nil
}
// DigitalRead reads digital value from pin
func (j *Adaptor) DigitalRead(pin string) (val int, err error) {
sysfsPin, err := j.DigitalPin(pin, sysfs.IN)
if err != nil {
return
}
return sysfsPin.Read()
}
// DigitalWrite writes digital value to specified pin
func (j *Adaptor) DigitalWrite(pin string, val byte) (err error) {
sysfsPin, err := j.DigitalPin(pin, sysfs.OUT)
if err != nil {
return err
}
return sysfsPin.Write(int(val))
}
// GetConnection returns an i2c connection to a device on a specified bus.
// Valid bus number is [0..1] which corresponds to /dev/i2c-0 through /dev/i2c-1.
func (j *Adaptor) GetConnection(address int, bus int) (connection i2c.Connection, err error) {
if (bus < 0) || (bus > 1) {
return nil, fmt.Errorf("Bus number %d out of range", bus)
}
device, err := j.getI2cBus(bus)
return i2c.NewConnection(device, address), err
}
// GetDefaultBus returns the default i2c bus for this platform
func (j *Adaptor) GetDefaultBus() int {
return j.i2cDefaultBus
}
// GetSpiConnection returns an spi connection to a device on a specified bus.
// Valid bus number is [0..1] which corresponds to /dev/spidev0.0 through /dev/spidev0.1.
func (j *Adaptor) GetSpiConnection(busNum, chipNum, mode, bits int, maxSpeed int64) (connection spi.Connection, err error) {
j.mutex.Lock()
defer j.mutex.Unlock()
if (busNum < 0) || (busNum > 1) {
return nil, fmt.Errorf("Bus number %d out of range", busNum)
}
if j.spiDevices[busNum] == nil {
j.spiDevices[busNum], err = spi.GetSpiConnection(busNum, chipNum, mode, bits, maxSpeed)
}
return j.spiDevices[busNum], err
}
// GetSpiDefaultBus returns the default spi bus for this platform.
func (j *Adaptor) GetSpiDefaultBus() int {
return j.spiDefaultBus
}
// GetSpiDefaultChip returns the default spi chip for this platform.
func (j *Adaptor) GetSpiDefaultChip() int {
return j.spiDefaultChip
}
// GetSpiDefaultMode returns the default spi mode for this platform.
func (j *Adaptor) GetSpiDefaultMode() int {
return j.spiDefaultMode
}
// GetSpiDefaultBits returns the default spi number of bits for this platform.
func (j *Adaptor) GetSpiDefaultBits() int {
return 8
}
// GetSpiDefaultMaxSpeed returns the default spi bus for this platform.
func (j *Adaptor) GetSpiDefaultMaxSpeed() int64 {
return j.spiDefaultMaxSpeed
}
//PWMPin returns a Jetson Nano. PWMPin which provides the sysfs.PWMPinner interface
func (j *Adaptor) PWMPin(pin string) (pwmPin sysfs.PWMPinner, err error) {
i, err := j.translatePin(pin)
if err != nil {
return
}
j.mutex.Lock()
defer j.mutex.Unlock()
if j.pwmPins[i] != nil {
return j.pwmPins[i], nil
}
j.pwmPins[i], err = NewPWMPin(pin)
if err != nil {
return
}
j.pwmPins[i].Export()
j.pwmPins[i].SetPeriod(pwmDefaultPeriod)
j.pwmPins[i].Enable(true)
return j.pwmPins[i], nil
}
// PwmWrite writes a PWM signal to the specified pin
func (j *Adaptor) PwmWrite(pin string, val byte) (err error) {
sysfsPin, err := j.PWMPin(pin)
if err != nil {
return err
}
duty := uint32(gobot.FromScale(float64(val), 0, 255) * float64(pwmDefaultPeriod))
return sysfsPin.SetDutyCycle(duty)
}
// ServoWrite writes a servo signal to the specified pin
func (j *Adaptor) ServoWrite(pin string, angle byte) (err error) {
sysfsPin, err := j.PWMPin(pin)
if err != nil {
return err
}
duty := uint32(gobot.FromScale(float64(angle), 0, 180) * float64(pwmDefaultPeriod))
return sysfsPin.SetDutyCycle(duty)
}
func (j *Adaptor) getExportedDigitalPin(translatedPin int, dir string) (sysfsPin sysfs.DigitalPinner, err error) {
j.mutex.Lock()
defer j.mutex.Unlock()
if j.digitalPins[translatedPin] == nil {
j.digitalPins[translatedPin] = sysfs.NewDigitalPin(translatedPin)
if err = j.digitalPins[translatedPin].Export(); err != nil {
return
}
}
return j.digitalPins[translatedPin], nil
}
func (j *Adaptor) getI2cBus(bus int) (_ i2c.I2cDevice, err error) {
j.mutex.Lock()
defer j.mutex.Unlock()
if j.i2cBuses[bus] == nil {
j.i2cBuses[bus], err = sysfs.NewI2cDevice(fmt.Sprintf("/dev/i2c-%d", bus))
}
return j.i2cBuses[bus], err
}
func (j *Adaptor) translatePin(pin string) (i int, err error) {
if val, ok := pins[pin][j.revision]; ok {
i = val
} else if val, ok := pins[pin]["*"]; ok {
i = val
} else {
err = errors.New("Not a valid pin")
return
}
return
}

View File

@ -0,0 +1,168 @@
package jetson
import (
"errors"
"strings"
"testing"
"runtime"
"strconv"
"sync"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/gpio"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/drivers/spi"
"gobot.io/x/gobot/gobottest"
"gobot.io/x/gobot/sysfs"
)
// make sure that this Adaptor fullfills all the required interfaces
var _ gobot.Adaptor = (*Adaptor)(nil)
var _ gpio.DigitalReader = (*Adaptor)(nil)
var _ gpio.DigitalWriter = (*Adaptor)(nil)
var _ sysfs.DigitalPinnerProvider = (*Adaptor)(nil)
var _ i2c.Connector = (*Adaptor)(nil)
var _ spi.Connector = (*Adaptor)(nil)
func initTestAdaptor() *Adaptor {
a := NewAdaptor()
a.Connect()
return a
}
func TestJetsonAdaptorName(t *testing.T) {
a := initTestAdaptor()
gobottest.Assert(t, strings.HasPrefix(a.Name(), "JetsonNano"), true)
a.SetName("NewName")
gobottest.Assert(t, a.Name(), "NewName")
}
func TestAdaptor(t *testing.T) {
a := NewAdaptor()
gobottest.Assert(t, strings.HasPrefix(a.Name(), "JetsonNano"), true)
gobottest.Assert(t, a.i2cDefaultBus, 1)
gobottest.Assert(t, a.revision, "")
}
func TestAdaptorFinalize(t *testing.T) {
a := initTestAdaptor()
fs := sysfs.NewMockFilesystem([]string{
"/sys/class/gpio/export",
"/sys/class/gpio/unexport",
"/dev/i2c-1",
"/dev/i2c-0",
"/dev/spidev0.0",
"/dev/spidev0.1",
})
sysfs.SetFilesystem(fs)
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.DigitalWrite("3", 1)
a.GetConnection(0xff, 0)
gobottest.Assert(t, a.Finalize(), nil)
}
func TestAdaptorDigitalIO(t *testing.T) {
a := initTestAdaptor()
fs := sysfs.NewMockFilesystem([]string{
"/sys/class/gpio/export",
"/sys/class/gpio/unexport",
"/sys/class/gpio/gpio216/value",
"/sys/class/gpio/gpio216/direction",
"/sys/class/gpio/gpio14/value",
"/sys/class/gpio/gpio14/direction",
})
sysfs.SetFilesystem(fs)
a.DigitalWrite("7", 1)
gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio216/value"].Contents, "1")
a.DigitalWrite("13", 1)
i, _ := a.DigitalRead("13")
gobottest.Assert(t, i, 1)
gobottest.Assert(t, a.DigitalWrite("notexist", 1), errors.New("Not a valid pin"))
fs.WithReadError = true
_, err := a.DigitalRead("7")
gobottest.Assert(t, err, errors.New("read error"))
fs.WithWriteError = true
_, err = a.DigitalRead("13")
gobottest.Assert(t, err, errors.New("write error"))
}
func TestAdaptorI2c(t *testing.T) {
a := initTestAdaptor()
fs := sysfs.NewMockFilesystem([]string{
"/dev/i2c-1",
})
sysfs.SetFilesystem(fs)
sysfs.SetSyscall(&sysfs.MockSyscall{})
con, err := a.GetConnection(0xff, 1)
gobottest.Assert(t, err, nil)
con.Write([]byte{0x00, 0x01})
data := []byte{42, 42}
con.Read(data)
gobottest.Assert(t, data, []byte{0x00, 0x01})
_, err = a.GetConnection(0xff, 51)
gobottest.Assert(t, err, errors.New("Bus number 51 out of range"))
gobottest.Assert(t, a.GetDefaultBus(), 1)
}
func TestAdaptorSPI(t *testing.T) {
a := initTestAdaptor()
fs := sysfs.NewMockFilesystem([]string{
"/dev/spidev0.1",
})
sysfs.SetFilesystem(fs)
sysfs.SetSyscall(&sysfs.MockSyscall{})
gobottest.Assert(t, a.GetSpiDefaultBus(), 0)
gobottest.Assert(t, a.GetSpiDefaultChip(), 0)
gobottest.Assert(t, a.GetSpiDefaultMode(), 0)
gobottest.Assert(t, a.GetSpiDefaultMaxSpeed(), int64(10000000))
_, err := a.GetSpiConnection(10, 0, 0, 8, 10000000)
gobottest.Assert(t, err.Error(), "Bus number 10 out of range")
// TODO: test tx/rx here...
}
func TestAdaptorDigitalPinConcurrency(t *testing.T) {
oldProcs := runtime.GOMAXPROCS(0)
runtime.GOMAXPROCS(8)
for retry := 0; retry < 20; retry++ {
a := initTestAdaptor()
var wg sync.WaitGroup
for i := 0; i < 20; i++ {
wg.Add(1)
pinAsString := strconv.Itoa(i)
go func(pin string) {
defer wg.Done()
a.DigitalPin(pin, sysfs.IN)
}(pinAsString)
}
wg.Wait()
}
runtime.GOMAXPROCS(oldProcs)
}

View File

@ -0,0 +1,75 @@
package jetson
var pins = map[string]map[string]int{
"7": {
"*": 216,
},
"11": {
"*": 50,
},
"12": {
"*": 79,
},
"13": {
"*": 14,
},
"15": {
"*": 194,
},
"16": {
"*": 232,
},
"18": {
"*": 15,
},
"19": {
"*": 16,
},
"21": {
"*": 17,
},
"22": {
"*": 13,
},
"23": {
"*": 18,
},
"24": {
"*": 19,
},
"26": {
"*": 20,
},
"29": {
"*": 149,
},
"31": {
"*": 200,
},
"32": {
"*": 168,
},
"33": {
"*": 38,
},
"35": {
"*": 76,
},
"36": {
"*": 51,
},
"37": {
"*": 12,
},
"38": {
"*": 77,
},
"40": {
"*": 78,
},
}
var pwms = map[string]string{
"32": "0",
"33": "2",
}

163
platforms/jetson/pwm_pin.go Normal file
View File

@ -0,0 +1,163 @@
package jetson
import (
"errors"
"fmt"
"os"
"gobot.io/x/gobot"
"gobot.io/x/gobot/sysfs"
)
const (
minimumPeriod = 5334
minimumRate = 0.05
)
// PWMPin is the Jetson Nano implementation of the PWMPinner interface.
// It uses gpio pwm.
type PWMPin struct {
pin string
fn string
dc uint32
period uint32
}
// NewPwmPin returns a new PWMPin
// pin32 pwm0, pin33 pwm2
func NewPWMPin(pin string) (p *PWMPin, err error) {
if val, ok := pwms[pin]; ok {
p = &PWMPin{pin: pin, fn: val}
} else {
err = errors.New("Not a valid pin")
}
return
}
// Export exports the pin for use by the Jetson Nano
func (p *PWMPin) Export() error {
fi, err := sysfs.OpenFile("/sys/class/pwm/pwmchip0/export", os.O_WRONLY|os.O_APPEND, 0644)
defer fi.Close()
if err != nil {
return err
}
_, err = fi.WriteString(p.fn)
return err
}
// Unexport unexports the pin and releases the pin from the operating system
func (p *PWMPin) Unexport() error {
fi, err := sysfs.OpenFile("/sys/class/pwm/pwmchip0/unexport", os.O_WRONLY|os.O_APPEND, 0644)
defer fi.Close()
if err != nil {
return err
}
_, err = fi.WriteString(p.fn)
return err
}
// Enable enables/disables the PWM pin
func (p *PWMPin) Enable(e bool) (err error) {
fi, err := sysfs.OpenFile(fmt.Sprintf("/sys/class/pwm/pwmchip0/pwm%s/enable", p.fn), os.O_WRONLY|os.O_APPEND, 0644)
defer fi.Close()
if err != nil {
return err
}
_, err = fi.WriteString(fmt.Sprintf("%v", bool2int(e)))
return err
}
// Polarity returns the polarity either normal or inverted
func (p *PWMPin) Polarity() (polarity string, err error) {
return "normal", nil
}
// InvertPolarity does not do anything when using Jetson Nano
func (p *PWMPin) InvertPolarity(invert bool) (err error) {
return nil
}
// Period returns the current PWM period for pin
func (p *PWMPin) Period() (period uint32, err error) {
if p.period == 0 {
return p.period, errors.New("Jetson PWM pin period not set")
}
return p.period, nil
}
// SetPeriod uses Jetson Nano setting and cannot be changed once set
func (p *PWMPin) SetPeriod(period uint32) (err error) {
if p.period != 0 {
return errors.New("Cannot set the period of individual PWM pins on Jetson")
}
// JetsonNano Minimum period
if period < minimumPeriod {
return errors.New("Cannot set the period more Then minimum.")
}
p.period = period
fi, err := sysfs.OpenFile(fmt.Sprintf("/sys/class/pwm/pwmchip0/pwm%s/period", p.fn), os.O_WRONLY|os.O_APPEND, 0644)
defer fi.Close()
if err != nil {
return err
}
_, err = fi.WriteString(fmt.Sprintf("%v", p.period))
return nil
}
// DutyCycle returns the duty cycle for the pin
func (p *PWMPin) DutyCycle() (duty uint32, err error) {
return p.dc, nil
}
// SetDutyCycle writes the duty cycle to the pin
func (p *PWMPin) SetDutyCycle(duty uint32) (err error) {
if p.period == 0 {
return errors.New("Jetson PWM pin period not set")
}
if duty > p.period {
return errors.New("Duty cycle exceeds period.")
}
p.dc = duty
rate := gobot.FromScale(float64(p.dc), 0, float64(p.period))
// never go below minimum allowed duty becuse very short duty
if rate < minimumRate {
duty = uint32(minimumRate * float64(p.period) / 100)
p.dc = duty
}
fi, err := sysfs.OpenFile(fmt.Sprintf("/sys/class/pwm/pwmchip0/pwm%s/duty_cycle", p.fn), os.O_WRONLY|os.O_APPEND, 0644)
defer fi.Close()
if err != nil {
return err
}
_, err = fi.WriteString(fmt.Sprintf("%v", duty))
return
}
func bool2int(b bool) int {
if b {
return 1
}
return 0
}

View File

@ -0,0 +1,57 @@
package jetson
import (
"errors"
"testing"
"gobot.io/x/gobot/gobottest"
"gobot.io/x/gobot/sysfs"
)
var _ sysfs.PWMPinner = (*PWMPin)(nil)
func TestPwmPin(t *testing.T) {
fs := sysfs.NewMockFilesystem([]string{
"/sys/class/pwm/pwmchip0/export",
"/sys/class/pwm/pwmchip0/unexport",
"/sys/class/pwm/pwmchip0/pwm0/enable",
"/sys/class/pwm/pwmchip0/pwm0/period",
"/sys/class/pwm/pwmchip0/pwm0/duty_cycle",
"/sys/class/pwm/pwmchip0/pwm2/enable",
"/sys/class/pwm/pwmchip0/pwm2/period",
"/sys/class/pwm/pwmchip0/pwm2/duty_cycle",
})
sysfs.SetFilesystem(fs)
pin, err := NewPWMPin("32")
gobottest.Assert(t, pin.Export(), nil)
gobottest.Assert(t, pin.Enable(true), nil)
val, _ := pin.Polarity()
gobottest.Assert(t, val, "normal")
gobottest.Assert(t, pin.InvertPolarity(true), nil)
val, _ = pin.Polarity()
gobottest.Assert(t, val, "normal")
period, err := pin.Period()
gobottest.Assert(t, err, errors.New("Jetson PWM pin period not set"))
gobottest.Assert(t, pin.SetDutyCycle(10000), errors.New("Jetson PWM pin period not set"))
gobottest.Assert(t, pin.SetPeriod(20000000), nil)
period, _ = pin.Period()
gobottest.Assert(t, period, uint32(20000000))
gobottest.Assert(t, pin.SetPeriod(10000000), errors.New("Cannot set the period of individual PWM pins on Jetson"))
dc, _ := pin.DutyCycle()
gobottest.Assert(t, dc, uint32(0))
gobottest.Assert(t, pin.SetDutyCycle(10000), nil)
dc, _ = pin.DutyCycle()
gobottest.Assert(t, dc, uint32(10000))
gobottest.Assert(t, pin.SetDutyCycle(999999999), errors.New("Duty cycle exceeds period."))
dc, _ = pin.DutyCycle()
gobottest.Assert(t, dc, uint32(10000))
gobottest.Assert(t, pin.Unexport(), nil)
}