Compare commits
27 Commits
781d9ccda4
...
v0.1.3
Author | SHA1 | Date | |
---|---|---|---|
6c110b9a8b | |||
cb07b6ac62 | |||
be99ed7fbf | |||
d625866d92 | |||
7ee03906f8 | |||
0b76884112 | |||
59bd2c5db3 | |||
0837d376f7 | |||
6a96656434 | |||
026c1aa3bb | |||
90a06e6afa | |||
e2e02ebbfe | |||
9bc94bfe7c | |||
061ba2a859 | |||
6498d20378 | |||
b831d44294 | |||
fd9e999b5a | |||
d05e2205d6 | |||
1b741c7dab | |||
e0110c558e | |||
225a0d2264 | |||
2eb21228e3 | |||
ebab41c510 | |||
92d42d413a | |||
b9056d2299 | |||
12555f2f46 | |||
eb899f0b45 |
1
.gitignore
vendored
1
.gitignore
vendored
@ -1,5 +1,4 @@
|
|||||||
out/
|
out/
|
||||||
Makefile
|
|
||||||
go.sum
|
go.sum
|
||||||
.git/
|
.git/
|
||||||
*.swp
|
*.swp
|
||||||
|
@ -4,6 +4,11 @@ WORKDIR /app
|
|||||||
COPY ./ ./
|
COPY ./ ./
|
||||||
RUN go mod download
|
RUN go mod download
|
||||||
|
|
||||||
|
RUN apt-get update
|
||||||
|
RUN apt-get install -y iputils-ping
|
||||||
|
RUN apt-get install -y ppp
|
||||||
|
RUN apt-get install -y net-tools
|
||||||
|
|
||||||
|
|
||||||
RUN CGO_ENABLED=0 GOOS=linux go build -o /modem-test
|
RUN CGO_ENABLED=0 GOOS=linux go build -o /modem-test
|
||||||
|
|
||||||
|
7
Makefile
Normal file
7
Makefile
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
export GOOS=linux
|
||||||
|
export GOARCH=arm
|
||||||
|
export GOARM=6
|
||||||
|
export CGO_ENABLED=0
|
||||||
|
|
||||||
|
build:
|
||||||
|
@go build -o out/modem main.go
|
@ -4,6 +4,7 @@ import (
|
|||||||
"fmt"
|
"fmt"
|
||||||
"io"
|
"io"
|
||||||
"log"
|
"log"
|
||||||
|
"sync"
|
||||||
"time"
|
"time"
|
||||||
|
|
||||||
"go.bug.st/serial"
|
"go.bug.st/serial"
|
||||||
@ -12,12 +13,14 @@ import (
|
|||||||
// Some constants
|
// Some constants
|
||||||
const (
|
const (
|
||||||
ReadTimeout = time.Second
|
ReadTimeout = time.Second
|
||||||
InputBufSize = 128
|
InputBufSize = 512
|
||||||
)
|
)
|
||||||
|
|
||||||
type atPort struct {
|
type atPort struct {
|
||||||
logger *log.Logger
|
logger *log.Logger
|
||||||
|
|
||||||
|
mutex sync.Mutex // Mutex for all operation with serial port
|
||||||
|
|
||||||
baudrate int
|
baudrate int
|
||||||
portName string
|
portName string
|
||||||
port serial.Port
|
port serial.Port
|
||||||
@ -26,12 +29,15 @@ type atPort struct {
|
|||||||
|
|
||||||
type Port interface {
|
type Port interface {
|
||||||
GetName() string
|
GetName() string
|
||||||
GetSerialPort() serial.Port // For extra need
|
GetBaudrate() int
|
||||||
|
SerialPort() serial.Port // For extra need
|
||||||
|
Mutex() sync.Locker // retruns pointer to mutex for advanced use like readign NMEA reports
|
||||||
|
|
||||||
Connect() error
|
Connect() error
|
||||||
Disconnect() error
|
Disconnect() error
|
||||||
IsConnected() bool
|
IsConnected() bool
|
||||||
|
|
||||||
|
RawSend(msg string) (string, error)
|
||||||
Send(cmd string) (Resp, error)
|
Send(cmd string) (Resp, error)
|
||||||
|
|
||||||
io.Closer
|
io.Closer
|
||||||
@ -50,11 +56,22 @@ func (p *atPort) GetName() string {
|
|||||||
return p.portName
|
return p.portName
|
||||||
}
|
}
|
||||||
|
|
||||||
func (p *atPort) GetSerialPort() serial.Port {
|
func (p *atPort) GetBaudrate() int {
|
||||||
|
return p.baudrate
|
||||||
|
}
|
||||||
|
|
||||||
|
func (p *atPort) SerialPort() serial.Port {
|
||||||
return p.port
|
return p.port
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func (p *atPort) Mutex() sync.Locker {
|
||||||
|
return &p.mutex
|
||||||
|
}
|
||||||
|
|
||||||
func (p *atPort) Connect() error {
|
func (p *atPort) Connect() error {
|
||||||
|
p.mutex.Lock()
|
||||||
|
defer p.mutex.Unlock()
|
||||||
|
|
||||||
p.logger.Println("Connecting to", p.portName, "...")
|
p.logger.Println("Connecting to", p.portName, "...")
|
||||||
s, err := serial.Open(p.portName, &serial.Mode{BaudRate: p.baudrate})
|
s, err := serial.Open(p.portName, &serial.Mode{BaudRate: p.baudrate})
|
||||||
if err != nil {
|
if err != nil {
|
||||||
@ -70,8 +87,10 @@ func (p *atPort) Connect() error {
|
|||||||
}
|
}
|
||||||
|
|
||||||
func (p *atPort) Disconnect() error {
|
func (p *atPort) Disconnect() error {
|
||||||
|
p.mutex.Lock()
|
||||||
defer func() {
|
defer func() {
|
||||||
p.port = nil
|
p.port = nil
|
||||||
|
p.mutex.Unlock()
|
||||||
}()
|
}()
|
||||||
if err := p.port.Close(); err != nil {
|
if err := p.port.Close(); err != nil {
|
||||||
return fmt.Errorf("close port: %w", err)
|
return fmt.Errorf("close port: %w", err)
|
||||||
@ -80,19 +99,25 @@ func (p *atPort) Disconnect() error {
|
|||||||
}
|
}
|
||||||
|
|
||||||
func (p *atPort) IsConnected() bool {
|
func (p *atPort) IsConnected() bool {
|
||||||
|
p.mutex.Lock()
|
||||||
|
defer p.mutex.Unlock()
|
||||||
|
|
||||||
return p.port != nil
|
return p.port != nil
|
||||||
}
|
}
|
||||||
|
|
||||||
// Low level write/read function
|
// Low level write/read function
|
||||||
func (p *atPort) makeReq(msg string) (string, error) {
|
func (p *atPort) RawSend(msg string) (string, error) {
|
||||||
|
p.mutex.Lock()
|
||||||
|
defer p.mutex.Unlock()
|
||||||
|
|
||||||
// Write
|
// Write
|
||||||
p.port.ResetInputBuffer()
|
|
||||||
if _, err := p.port.Write([]byte(msg)); err != nil {
|
if _, err := p.port.Write([]byte(msg)); err != nil {
|
||||||
return "", fmt.Errorf("serial port write: %w", err)
|
return "", fmt.Errorf("serial port write: %w", err)
|
||||||
}
|
}
|
||||||
|
// time.Sleep(time.Millisecond)
|
||||||
// Read
|
// Read
|
||||||
readLen, err := p.port.Read(p.inputBuf)
|
readLen, err := p.port.Read(p.inputBuf)
|
||||||
p.logger.Println(msg, "RAWREAD:", string(p.inputBuf[:readLen]))
|
// p.logger.Println(msg, "\x1b[38;2;150;150;150mRAWREAD:", string(p.inputBuf[:readLen]), "\x1b[38;2;255;255;255m")
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return "", fmt.Errorf("port read: %w", err)
|
return "", fmt.Errorf("port read: %w", err)
|
||||||
}
|
}
|
||||||
@ -102,12 +127,12 @@ func (p *atPort) makeReq(msg string) (string, error) {
|
|||||||
|
|
||||||
func (p *atPort) Send(cmd string) (Resp, error) {
|
func (p *atPort) Send(cmd string) (Resp, error) {
|
||||||
cmd += "\r\n"
|
cmd += "\r\n"
|
||||||
rawResp, err := p.makeReq(cmd)
|
rawResp, err := p.RawSend(cmd)
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return RespNil, fmt.Errorf("make request: %w", err)
|
return RespNil, fmt.Errorf("make request: %w", err)
|
||||||
}
|
}
|
||||||
if len(rawResp) <= 4 {
|
if len(rawResp) <= 4 {
|
||||||
return RespNil, fmt.Errorf("read too small msg: %d byte", len(rawResp))
|
return RespNil, fmt.Errorf("read too small msg: %d byte - %s", len(rawResp), string(rawResp))
|
||||||
}
|
}
|
||||||
resp := rawResp[2 : len(rawResp)-2] // Cut \r\n
|
resp := rawResp[2 : len(rawResp)-2] // Cut \r\n
|
||||||
|
|
||||||
@ -115,5 +140,8 @@ func (p *atPort) Send(cmd string) (Resp, error) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
func (p *atPort) Close() error {
|
func (p *atPort) Close() error {
|
||||||
|
p.mutex.Lock()
|
||||||
|
defer p.mutex.Unlock()
|
||||||
|
|
||||||
return p.port.Close()
|
return p.port.Close()
|
||||||
}
|
}
|
||||||
|
@ -9,9 +9,16 @@ func (resp Resp) Check() bool {
|
|||||||
}
|
}
|
||||||
|
|
||||||
func (resp Resp) RmFront(str string) Resp {
|
func (resp Resp) RmFront(str string) Resp {
|
||||||
|
if !resp.Check() {
|
||||||
|
return RespNil
|
||||||
|
}
|
||||||
return Resp(string(resp)[len(str):])
|
return Resp(string(resp)[len(str):])
|
||||||
}
|
}
|
||||||
|
|
||||||
func (resp Resp) String() string {
|
func (resp Resp) String() string {
|
||||||
return string(resp)
|
return string(resp)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func (resp Resp) Bytes() []byte {
|
||||||
|
return []byte(resp)
|
||||||
|
}
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
package modem
|
package gpio
|
||||||
|
|
||||||
import (
|
import (
|
||||||
|
"io"
|
||||||
"log"
|
"log"
|
||||||
"time"
|
"time"
|
||||||
|
|
||||||
@ -9,7 +10,21 @@ import (
|
|||||||
|
|
||||||
type gpioPin struct {
|
type gpioPin struct {
|
||||||
logger *log.Logger
|
logger *log.Logger
|
||||||
Pin gpio.Pin
|
pin gpio.Pin
|
||||||
|
}
|
||||||
|
|
||||||
|
type Pin interface {
|
||||||
|
Init() error
|
||||||
|
PowerOn()
|
||||||
|
PowerOff()
|
||||||
|
io.Closer
|
||||||
|
}
|
||||||
|
|
||||||
|
func New(logger *log.Logger, pin uint8) Pin {
|
||||||
|
return gpioPin{
|
||||||
|
logger: logger,
|
||||||
|
pin: gpio.Pin(pin),
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
func (p gpioPin) Init() error {
|
func (p gpioPin) Init() error {
|
||||||
@ -17,20 +32,20 @@ func (p gpioPin) Init() error {
|
|||||||
}
|
}
|
||||||
|
|
||||||
func (p gpioPin) sendOnOffSignal() {
|
func (p gpioPin) sendOnOffSignal() {
|
||||||
p.Pin.Output()
|
p.pin.Output()
|
||||||
p.logger.Println("Power on 0/3 + 100ms")
|
p.logger.Println("Power on 0/3 + 100ms")
|
||||||
p.Pin.Low()
|
p.pin.Low()
|
||||||
p.Pin.Toggle()
|
p.pin.Toggle()
|
||||||
time.Sleep(100 * time.Millisecond)
|
time.Sleep(100 * time.Millisecond)
|
||||||
|
|
||||||
p.logger.Println("Power on 1/3 + 3s")
|
p.logger.Println("Power on 1/3 + 3s")
|
||||||
p.Pin.High()
|
p.pin.High()
|
||||||
p.Pin.Toggle()
|
p.pin.Toggle()
|
||||||
time.Sleep(3 * time.Second)
|
time.Sleep(3 * time.Second)
|
||||||
|
|
||||||
p.logger.Println("Power on 2/3 + 30s")
|
p.logger.Println("Power on 2/3 + 30s")
|
||||||
p.Pin.Low()
|
p.pin.Low()
|
||||||
p.Pin.Toggle()
|
p.pin.Toggle()
|
||||||
time.Sleep(30 * time.Second)
|
time.Sleep(30 * time.Second)
|
||||||
|
|
||||||
p.logger.Println("Power on 3/3")
|
p.logger.Println("Power on 3/3")
|
||||||
@ -40,10 +55,10 @@ func (p gpioPin) PowerOn() {
|
|||||||
p.sendOnOffSignal()
|
p.sendOnOffSignal()
|
||||||
}
|
}
|
||||||
|
|
||||||
func (p *gpioPin) PowerOff() {
|
func (p gpioPin) PowerOff() {
|
||||||
p.sendOnOffSignal()
|
p.sendOnOffSignal()
|
||||||
}
|
}
|
||||||
|
|
||||||
func (p *gpioPin) Close() error {
|
func (p gpioPin) Close() error {
|
||||||
return gpio.Close()
|
return gpio.Close()
|
||||||
}
|
}
|
@ -1,14 +1,16 @@
|
|||||||
package modem
|
package gps
|
||||||
|
|
||||||
import (
|
import (
|
||||||
"fmt"
|
"fmt"
|
||||||
|
"io"
|
||||||
|
"log"
|
||||||
"math"
|
"math"
|
||||||
"strconv"
|
"strconv"
|
||||||
"strings"
|
"strings"
|
||||||
"time"
|
"time"
|
||||||
)
|
)
|
||||||
|
|
||||||
type GpsData struct {
|
type Data struct {
|
||||||
Latitude float64 `json:"Latitude"`
|
Latitude float64 `json:"Latitude"`
|
||||||
Longitude float64 `json:"Longitude"`
|
Longitude float64 `json:"Longitude"`
|
||||||
LatitudeIndicator string `json:"Latitude_indicator"` // North/South
|
LatitudeIndicator string `json:"Latitude_indicator"` // North/South
|
||||||
@ -20,13 +22,13 @@ type GpsData struct {
|
|||||||
Time string `json:"-"`
|
Time string `json:"-"`
|
||||||
}
|
}
|
||||||
|
|
||||||
var GpsInfoNil = GpsData{}
|
var GpsInfoNil = Data{}
|
||||||
|
|
||||||
func deg2rad(deg float64) float64 {
|
func deg2rad(deg float64) float64 {
|
||||||
return deg * (math.Pi / 180)
|
return deg * (math.Pi / 180)
|
||||||
}
|
}
|
||||||
|
|
||||||
func (gps *GpsData) calculateSpeed(newLatitude, newLongitude float64, lastUpdateTime time.Time) {
|
func (gps *Data) CalculateSpeed(newLatitude, newLongitude float64, lastUpdateTime time.Time) {
|
||||||
earthRad := 6371.0 // TODO ?
|
earthRad := 6371.0 // TODO ?
|
||||||
dLat := deg2rad(math.Abs(newLatitude - gps.Latitude))
|
dLat := deg2rad(math.Abs(newLatitude - gps.Latitude))
|
||||||
dLon := deg2rad(math.Abs(newLongitude - gps.Longitude))
|
dLon := deg2rad(math.Abs(newLongitude - gps.Longitude))
|
||||||
@ -37,36 +39,45 @@ func (gps *GpsData) calculateSpeed(newLatitude, newLongitude float64, lastUpdate
|
|||||||
gps.Speed = earthRad * c / (math.Abs(float64(time.Since(lastUpdateTime))))
|
gps.Speed = earthRad * c / (math.Abs(float64(time.Since(lastUpdateTime))))
|
||||||
}
|
}
|
||||||
|
|
||||||
func (gps *GpsData) decode(str string) error {
|
// To remove warning
|
||||||
var err error
|
|
||||||
newGpsInfo := GpsData{}
|
|
||||||
strs := strings.Split(strings.Split(strings.Replace(str, " ", "", -1), "\n")[0], ",")
|
|
||||||
|
|
||||||
|
// Parse string from AT command that contains gps data
|
||||||
|
func (gps *Data) decode(str string) error {
|
||||||
|
var err error
|
||||||
|
newGpsInfo := Data{}
|
||||||
|
strs := strings.Split(strings.Split(strings.Replace(str, " ", "", -1), "\n")[0], ",")
|
||||||
|
logger := log.New(io.Discard, "modem-gps", log.LstdFlags)
|
||||||
|
|
||||||
|
if len(strs) < 7 {
|
||||||
|
return fmt.Errorf("ERROR: too small msg: %s", strs)
|
||||||
|
}
|
||||||
newGpsInfo.Latitude, err = strconv.ParseFloat(strs[0], 64)
|
newGpsInfo.Latitude, err = strconv.ParseFloat(strs[0], 64)
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("parse latitude: %w", err)
|
logger.Println("ERROR parse latitude:", err.Error())
|
||||||
}
|
}
|
||||||
newGpsInfo.Longitude, err = strconv.ParseFloat(strs[2], 64)
|
newGpsInfo.Longitude, err = strconv.ParseFloat(strs[2], 64)
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("parse longitude: %w", err)
|
logger.Println("ERROR parse longitude:", err.Error())
|
||||||
}
|
}
|
||||||
|
newGpsInfo.Latitude /= 100
|
||||||
|
newGpsInfo.Longitude /= 100
|
||||||
newGpsInfo.LatitudeIndicator = strs[1]
|
newGpsInfo.LatitudeIndicator = strs[1]
|
||||||
newGpsInfo.LatitudeIndicator = strs[3]
|
newGpsInfo.LongitudeIndicator = strs[3]
|
||||||
newGpsInfo.Date = strs[4]
|
newGpsInfo.Date = strs[4]
|
||||||
newGpsInfo.Time = strs[5]
|
newGpsInfo.Time = strs[5]
|
||||||
newGpsInfo.Altitude, err = strconv.ParseFloat(strs[6], 64)
|
newGpsInfo.Altitude, err = strconv.ParseFloat(strs[6], 64)
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("parse altitude: %w", err)
|
logger.Println("ERROR parse altitude:", err.Error())
|
||||||
}
|
}
|
||||||
newGpsInfo.Speed, err = strconv.ParseFloat(strs[7], 64)
|
newGpsInfo.Speed, err = strconv.ParseFloat(strs[7], 64)
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("parse speed: %w", err)
|
logger.Println("ERROR parse speed:", err.Error())
|
||||||
}
|
}
|
||||||
// Course sometimes may be null
|
// Course sometimes may be null
|
||||||
if len(strs[8]) > 0 {
|
if len(strs[8]) > 0 {
|
||||||
newGpsInfo.Course, err = strconv.ParseFloat(strs[8], 64)
|
newGpsInfo.Course, err = strconv.ParseFloat(strs[8], 64)
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("parse course: %w", err)
|
logger.Println("ERROR parse course:", err.Error())
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
*gps = newGpsInfo
|
*gps = newGpsInfo
|
106
api/modem/gps/gps.go
Normal file
106
api/modem/gps/gps.go
Normal file
@ -0,0 +1,106 @@
|
|||||||
|
package gps
|
||||||
|
|
||||||
|
import (
|
||||||
|
"fmt"
|
||||||
|
"io"
|
||||||
|
"log"
|
||||||
|
"strings"
|
||||||
|
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/at"
|
||||||
|
)
|
||||||
|
|
||||||
|
type gps struct {
|
||||||
|
logger *log.Logger
|
||||||
|
port at.Port
|
||||||
|
data Data
|
||||||
|
}
|
||||||
|
|
||||||
|
type Gps interface {
|
||||||
|
Init() error
|
||||||
|
Update() error
|
||||||
|
|
||||||
|
GetData() Data
|
||||||
|
GetStatus() (Status, error)
|
||||||
|
|
||||||
|
io.Closer
|
||||||
|
}
|
||||||
|
|
||||||
|
func New(logger *log.Logger, port at.Port) Gps {
|
||||||
|
return &gps{
|
||||||
|
logger: logger,
|
||||||
|
port: port,
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) Init() error {
|
||||||
|
if !g.port.IsConnected() {
|
||||||
|
return fmt.Errorf("at port is not connected")
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) Update() error {
|
||||||
|
if err := g.switchGpsMode(true); err != nil {
|
||||||
|
return fmt.Errorf("try to GPS mode: %w", err)
|
||||||
|
}
|
||||||
|
defer g.switchGpsMode(false)
|
||||||
|
|
||||||
|
resp, err := g.port.Send("AT+CGPSINFO")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("receive GPS data: %w", err)
|
||||||
|
}
|
||||||
|
if !resp.Check() {
|
||||||
|
return fmt.Errorf("get GPS info: error response: %s", resp)
|
||||||
|
}
|
||||||
|
if err := g.data.decode(strings.Split(strings.Replace(resp.RmFront("+CGPSINFO:").String(), "\r", "", -1), "\n")[0]); err != nil {
|
||||||
|
g.logger.Printf("error decode: %s\n", err.Error())
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) GetData() Data {
|
||||||
|
return g.data
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) Close() error {
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) switchGpsMode(on bool) error {
|
||||||
|
onStr := "0"
|
||||||
|
if on {
|
||||||
|
onStr = "1"
|
||||||
|
}
|
||||||
|
|
||||||
|
// Reset input
|
||||||
|
if err := g.port.SerialPort().ResetInputBuffer(); err != nil {
|
||||||
|
return fmt.Errorf("reset input buffer: %w", err)
|
||||||
|
}
|
||||||
|
// Reset output
|
||||||
|
if err := g.port.SerialPort().ResetOutputBuffer(); err != nil {
|
||||||
|
return fmt.Errorf("reset output buffer: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check gps mode status
|
||||||
|
resp, err := g.port.Send("AT+CGPS?")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("make at ask: %w", err)
|
||||||
|
}
|
||||||
|
if !resp.Check() {
|
||||||
|
return fmt.Errorf("get GPS mode: error response: %s", resp)
|
||||||
|
}
|
||||||
|
ans := strings.Replace(strings.Split(strings.Split(resp.RmFront("+CGPS:").String(), "\n")[0], ",")[0], " ", "", -1)
|
||||||
|
if ans == onStr {
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
// Modem is not in GPS mode
|
||||||
|
resp, err = g.port.Send("AT+CGPS=" + onStr)
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("set GPS mode: %w", err)
|
||||||
|
}
|
||||||
|
if !resp.Check() {
|
||||||
|
return fmt.Errorf("set GPS mode: error response: %s", resp)
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
149
api/modem/gps/nmea.go
Normal file
149
api/modem/gps/nmea.go
Normal file
@ -0,0 +1,149 @@
|
|||||||
|
package gps
|
||||||
|
|
||||||
|
import (
|
||||||
|
"fmt"
|
||||||
|
"log"
|
||||||
|
"strings"
|
||||||
|
"time"
|
||||||
|
)
|
||||||
|
|
||||||
|
type nmeaFlags int
|
||||||
|
|
||||||
|
const (
|
||||||
|
gga nmeaFlags = 1 << iota // global positioning systemfix data
|
||||||
|
rmc // recommended minimumspecific GPS/TRANSIT data
|
||||||
|
gpgsv // GPS satellites in view
|
||||||
|
gpgsa // GPS DOP and active satellites
|
||||||
|
vtg // track made good and ground speed
|
||||||
|
xfi // Global Positioning SystemExtended FixData.)Bit 6 – GLGSV (GLONASS satellites in view GLONASSfixesonly
|
||||||
|
glgsa // 1. GPS/2. Glonass/3. GALILE DOPandActiveSatellites.
|
||||||
|
gns // fix data for GNSS receivers; output for GPS, GLONASS, GALILEO
|
||||||
|
_ // Reserved
|
||||||
|
gagsv // GALILEO satellites in view
|
||||||
|
_ // Reserved
|
||||||
|
_ // Reserved
|
||||||
|
_ // Reserved
|
||||||
|
_ // Reserved
|
||||||
|
_ // Reserved
|
||||||
|
bdpqgsa // BEIDOU/QZSS DOP and activesatellites
|
||||||
|
bdpqgsv // BEIDOUQZSS satellites in view
|
||||||
|
|
||||||
|
nmeaFlagsMask = (1 << 18) - 1
|
||||||
|
|
||||||
|
collectTimeout = 1 * time.Second
|
||||||
|
)
|
||||||
|
|
||||||
|
func secondCountDownTimer(title string, logger *log.Logger, t time.Duration) {
|
||||||
|
counter := 0
|
||||||
|
for {
|
||||||
|
if counter > int(t.Seconds()) {
|
||||||
|
break
|
||||||
|
}
|
||||||
|
logger.Printf("%s: %d/%f\n", title, counter, t.Seconds())
|
||||||
|
time.Sleep(time.Second)
|
||||||
|
counter += 1
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Go... otherwise will throw warning
|
||||||
|
var nmeaFlagsAll = gga | rmc | gpgsv | gpgsa | vtg | xfi | glgsa | gns | gagsv | bdpqgsa | bdpqgsv
|
||||||
|
|
||||||
|
func (g *gps) rawCollect(flags nmeaFlags) (string, error) {
|
||||||
|
// Need to omplement low level write/read here because collect must be atomic operation
|
||||||
|
// If other command is executed(write/read) it will read a part of nmea report and cause an error
|
||||||
|
|
||||||
|
// Setup gps
|
||||||
|
|
||||||
|
// Set output rate to 10Hz
|
||||||
|
if resp, err := g.port.Send("AT+CGPSNMEARATE=1"); err != nil {
|
||||||
|
return "", fmt.Errorf("AT+CGPSNMEARATE= request: %w", err)
|
||||||
|
} else {
|
||||||
|
if !resp.Check() {
|
||||||
|
return "", fmt.Errorf("set output rate: error response: %s", resp)
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
g.switchGpsMode(true)
|
||||||
|
g.port.Mutex().Lock()
|
||||||
|
s := g.port.SerialPort()
|
||||||
|
defer func() {
|
||||||
|
g.port.Mutex().Unlock()
|
||||||
|
g.switchGpsMode(false)
|
||||||
|
}()
|
||||||
|
|
||||||
|
// Send AT+CGPSINFOCFG=255, flags
|
||||||
|
flags &= nmeaFlagsMask
|
||||||
|
if _, err := s.Write([]byte("AT+CGPSINFOCFG=1,31\r\n")); err != nil {
|
||||||
|
return "", fmt.Errorf("serial port write 1: %w", err)
|
||||||
|
}
|
||||||
|
// Do I need to read answer
|
||||||
|
|
||||||
|
// Wait
|
||||||
|
secondCountDownTimer("Collecting NMEA data", g.logger, collectTimeout)
|
||||||
|
|
||||||
|
// Send AT+CGPSINFOCFG=0, flags
|
||||||
|
if _, err := s.Write([]byte("AT+CGPSINFOCFG=0,31\r\n")); err != nil {
|
||||||
|
return "", fmt.Errorf("serial port write 2: %w", err)
|
||||||
|
}
|
||||||
|
if _, err := s.Write([]byte("AT+CGPSFTM=0\r\n")); err != nil { // For sure because sometimes it cannot stop...
|
||||||
|
return "", fmt.Errorf("serial port write 2: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
time.Sleep(100 * time.Millisecond) // To enshure
|
||||||
|
|
||||||
|
// Read
|
||||||
|
outBuf := make([]byte, 0)
|
||||||
|
buf := make([]byte, 128)
|
||||||
|
|
||||||
|
readLoop:
|
||||||
|
for {
|
||||||
|
n, err := s.Read(buf)
|
||||||
|
if err != nil {
|
||||||
|
return string(outBuf), fmt.Errorf("serial port read: %w", err)
|
||||||
|
}
|
||||||
|
if n == 0 {
|
||||||
|
break readLoop
|
||||||
|
}
|
||||||
|
outBuf = append(outBuf, buf[:n]...)
|
||||||
|
}
|
||||||
|
|
||||||
|
return string(outBuf), nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) collectNmeaReports(flags nmeaFlags) ([]string, error) {
|
||||||
|
// Raw collect
|
||||||
|
resp, err := g.rawCollect(flags)
|
||||||
|
if err != nil {
|
||||||
|
return nil, fmt.Errorf("raw collect: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
// DEBUG
|
||||||
|
// g.logger.Println("NMEA raw collect:", resp)
|
||||||
|
|
||||||
|
// Right responce struct:
|
||||||
|
// \r\n
|
||||||
|
// OK
|
||||||
|
// \r\n
|
||||||
|
// (NMEA sentence)...
|
||||||
|
// \r\n
|
||||||
|
// OK
|
||||||
|
// \r\n
|
||||||
|
strs := strings.Split(strings.Replace(resp, "\r", "", -1), "\n")
|
||||||
|
|
||||||
|
// Check
|
||||||
|
// Now wait for:
|
||||||
|
// OK
|
||||||
|
// (NMEA sentence)...
|
||||||
|
// OK
|
||||||
|
// if len(strs) < 2 {
|
||||||
|
// return nil, fmt.Errorf("responce too few rows: %d", len(strs))
|
||||||
|
// }
|
||||||
|
// if !(strs[0] == "OK" && strs[len(strs)-1] == "OK") {
|
||||||
|
// return nil, fmt.Errorf("not OK responce: [% s]", strs)
|
||||||
|
// }
|
||||||
|
|
||||||
|
// This... response is not stable
|
||||||
|
// Every time it gives one or two OK and in ramdom order
|
||||||
|
// So I will not check gor it
|
||||||
|
return strs, nil
|
||||||
|
}
|
151
api/modem/gps/status.go
Normal file
151
api/modem/gps/status.go
Normal file
@ -0,0 +1,151 @@
|
|||||||
|
package gps
|
||||||
|
|
||||||
|
import (
|
||||||
|
"fmt"
|
||||||
|
"strconv"
|
||||||
|
"strings"
|
||||||
|
)
|
||||||
|
|
||||||
|
type Status struct {
|
||||||
|
GotResponses bool `json:"gotResponses"`
|
||||||
|
IsValidData bool `json:"isValidData"`
|
||||||
|
FoundSatelitesCount int `json:"foundSatelitesCount"`
|
||||||
|
ActiveSatelitesCount int `json:"activeSatelitesCount"`
|
||||||
|
Rms float32 `json:"rms"` // Root mean square
|
||||||
|
}
|
||||||
|
|
||||||
|
var StatusNil = Status{
|
||||||
|
GotResponses: false,
|
||||||
|
IsValidData: false,
|
||||||
|
FoundSatelitesCount: 0,
|
||||||
|
ActiveSatelitesCount: 0,
|
||||||
|
Rms: 0,
|
||||||
|
}
|
||||||
|
|
||||||
|
func (g *gps) GetStatus() (Status, error) {
|
||||||
|
// Provides more information about signal and possible problems using NMEA reports
|
||||||
|
|
||||||
|
// Collect reports
|
||||||
|
reports, err := g.collectNmeaReports(nmeaFlagsAll) // Now minimum
|
||||||
|
if err != nil {
|
||||||
|
return StatusNil, fmt.Errorf("collect nmea reports: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Annalise
|
||||||
|
st := Status{}
|
||||||
|
|
||||||
|
checkLoop:
|
||||||
|
for _, s := range reports {
|
||||||
|
// Check for NMEA format
|
||||||
|
if len(s) < 1 || s[0] != '$' {
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
st.GotResponses = true
|
||||||
|
|
||||||
|
g.logger.Println("NMEA check:", s)
|
||||||
|
values := strings.Split(s, ",")
|
||||||
|
if len(values[0]) != 6 {
|
||||||
|
return StatusNil, fmt.Errorf("nmea invalid sentence: %s", s)
|
||||||
|
}
|
||||||
|
switch values[0][3:] { // Switch by content
|
||||||
|
case "GSV": // Any satelites
|
||||||
|
g.logger.Println("check GSV")
|
||||||
|
// Check len
|
||||||
|
if len(values) < 17 {
|
||||||
|
g.logger.Println("GSV too small values")
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
|
||||||
|
// Decode
|
||||||
|
// 0 - msg type
|
||||||
|
// 1 - number of msgs
|
||||||
|
// 2 - index of this msg
|
||||||
|
// 3 - number of visible satelites
|
||||||
|
// 4: - other data
|
||||||
|
|
||||||
|
// Msg index
|
||||||
|
index, err := strconv.Atoi(values[3])
|
||||||
|
if err != nil {
|
||||||
|
g.logger.Println("GSV too small values")
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
_ = index
|
||||||
|
// if index != 0 {
|
||||||
|
// g.logger.Println("discard not first GSV msg")
|
||||||
|
// continue checkLoop
|
||||||
|
// }
|
||||||
|
|
||||||
|
// Count
|
||||||
|
satCount, err := strconv.Atoi(values[4])
|
||||||
|
if err != nil {
|
||||||
|
g.logger.Println("GSV too small values")
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
st.FoundSatelitesCount = satCount
|
||||||
|
case "GSA": // Active satelites
|
||||||
|
g.logger.Println("check GSA")
|
||||||
|
|
||||||
|
// Check len
|
||||||
|
if len(values) < 17 {
|
||||||
|
g.logger.Println("GSV too small values")
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
|
||||||
|
// Decode
|
||||||
|
// 0 - msg type
|
||||||
|
// 1 - mode of selecting format
|
||||||
|
// 2 - mode of selected format
|
||||||
|
// 3:15 - IDs of active satelites
|
||||||
|
// 15: - other data
|
||||||
|
|
||||||
|
// Counting active satelites
|
||||||
|
count := 0
|
||||||
|
for _, v := range values[3:15] {
|
||||||
|
if _, err := strconv.Atoi(v); err == nil {
|
||||||
|
count += 1
|
||||||
|
}
|
||||||
|
}
|
||||||
|
st.ActiveSatelitesCount = max(st.ActiveSatelitesCount, count)
|
||||||
|
case "RMC": // Minimum GPS data
|
||||||
|
g.logger.Println("check RMC")
|
||||||
|
// Check len
|
||||||
|
if len(values) < 12 {
|
||||||
|
g.logger.Println("RMC too small values")
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
|
||||||
|
// Decode
|
||||||
|
// 0 - msg type
|
||||||
|
// 1 - time
|
||||||
|
// 2 - is data valid or not
|
||||||
|
// 3: - other data
|
||||||
|
|
||||||
|
// Is valid value
|
||||||
|
if values[2] == "A" {
|
||||||
|
st.IsValidData = true
|
||||||
|
}
|
||||||
|
case "GST":
|
||||||
|
g.logger.Println("check GST")
|
||||||
|
// Check len
|
||||||
|
if len(values) < 8 {
|
||||||
|
g.logger.Println("GST too small values")
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
|
||||||
|
// Decode
|
||||||
|
// 0 - msg type
|
||||||
|
// 1 - time
|
||||||
|
// 2 - Root Mean Square
|
||||||
|
// 3: - other data
|
||||||
|
|
||||||
|
rms, err := strconv.ParseFloat(values[2], 32)
|
||||||
|
if err != nil {
|
||||||
|
g.logger.Println("RMS decode:", err.Error())
|
||||||
|
continue checkLoop
|
||||||
|
}
|
||||||
|
st.Rms = float32(rms)
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return st, nil
|
||||||
|
}
|
241
api/modem/internet/ic.go
Normal file
241
api/modem/internet/ic.go
Normal file
@ -0,0 +1,241 @@
|
|||||||
|
package internet
|
||||||
|
|
||||||
|
import (
|
||||||
|
"fmt"
|
||||||
|
"io"
|
||||||
|
"log"
|
||||||
|
"os"
|
||||||
|
"os/exec"
|
||||||
|
"strings"
|
||||||
|
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/at"
|
||||||
|
)
|
||||||
|
|
||||||
|
var apns = map[string]string{
|
||||||
|
"Tinkoff": "m.tinkoff",
|
||||||
|
}
|
||||||
|
|
||||||
|
const pppConfigName = "annalistnet"
|
||||||
|
const pppConfig = `
|
||||||
|
# Annalist project custom internet connection
|
||||||
|
|
||||||
|
# APN:
|
||||||
|
connect "/usr/sbin/chat -v -f /etc/chatscripts/gprs -T %s"
|
||||||
|
|
||||||
|
# Port:
|
||||||
|
%s
|
||||||
|
|
||||||
|
# Baudrate:
|
||||||
|
%d
|
||||||
|
|
||||||
|
noipdefault
|
||||||
|
usepeerdns
|
||||||
|
defaultroute
|
||||||
|
persist
|
||||||
|
noauth
|
||||||
|
nocrtscts
|
||||||
|
local
|
||||||
|
`
|
||||||
|
|
||||||
|
type conn struct {
|
||||||
|
logger *log.Logger
|
||||||
|
port at.Port
|
||||||
|
}
|
||||||
|
|
||||||
|
type Conn interface {
|
||||||
|
Init() error
|
||||||
|
ConfigurePPP() error
|
||||||
|
Ping() bool // Is connected
|
||||||
|
io.Closer
|
||||||
|
}
|
||||||
|
|
||||||
|
func New(logger *log.Logger, port at.Port) Conn {
|
||||||
|
return &conn{
|
||||||
|
logger: logger,
|
||||||
|
port: port,
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) checkPackageExist(pname string) bool {
|
||||||
|
resp, err := exec.Command("apt-mark", "showmanual", pname).Output()
|
||||||
|
c.logger.Println("CHECK:", resp)
|
||||||
|
if err != nil {
|
||||||
|
c.logger.Println("CHECK PACKAGE ERROR: ", err.Error())
|
||||||
|
return false
|
||||||
|
}
|
||||||
|
return string(resp[:len(pname)]) == pname
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) ensurePackage(pname string) error {
|
||||||
|
if c.checkPackageExist(pname) {
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
return fmt.Errorf("package %s not installed", pname)
|
||||||
|
// c.logger.Println("Installing", pname, "package...")
|
||||||
|
// resp, err := exec.Command("apt-get", "install", pname).Output()
|
||||||
|
// if err != nil {
|
||||||
|
// return fmt.Errorf("execute install cmd: %w", err)
|
||||||
|
// }
|
||||||
|
// c.logger.Println(resp)
|
||||||
|
// c.logger.Println("\x1b[38;2;255;0;0mComplete\x1b[38;2;255;255;255m")
|
||||||
|
// return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check requirenments
|
||||||
|
func (c *conn) checkReqs() error {
|
||||||
|
// Check AT port for sure
|
||||||
|
if c.port == nil || !c.port.IsConnected() {
|
||||||
|
return fmt.Errorf("AT port is not connect or nil")
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ensure all necessary packages installed
|
||||||
|
if err := c.ensurePackage("ppp"); err != nil {
|
||||||
|
return fmt.Errorf("ensure ppp package: %w", err)
|
||||||
|
}
|
||||||
|
// if err := c.ensurePackage("net-tools"); err != nil {
|
||||||
|
// return fmt.Errorf("ensure net-tools package: %w", err)
|
||||||
|
// }
|
||||||
|
|
||||||
|
// Check SIM is valid
|
||||||
|
// AT+CPIN? and just check
|
||||||
|
resp, err := c.port.Send("AT+CPIN?")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("AT+CPIN? request: %w", err)
|
||||||
|
}
|
||||||
|
if !resp.Check() {
|
||||||
|
return fmt.Errorf("validate SIM: error response: %s", resp)
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) ConfigurePPP() error {
|
||||||
|
// Get provider name and its APN
|
||||||
|
resp, err := c.port.Send("AT+CSPN?")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("AT+CSPN? request: %w", err)
|
||||||
|
}
|
||||||
|
if !resp.Check() {
|
||||||
|
return fmt.Errorf("get provider: error response: %s", resp)
|
||||||
|
}
|
||||||
|
strs := strings.Split(string(resp), "\"")
|
||||||
|
if len(strs) < 3 {
|
||||||
|
return fmt.Errorf("parse AT+CSPN response: %s", string(resp))
|
||||||
|
}
|
||||||
|
provider := strs[1]
|
||||||
|
apn := apns[provider]
|
||||||
|
if apn == "" {
|
||||||
|
return fmt.Errorf("no apn for provider: %s", provider)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Make config
|
||||||
|
c.logger.Printf("Config values: %s, %s, %d", apn, c.port.GetName(), c.port.GetBaudrate())
|
||||||
|
config := fmt.Sprintf(pppConfig, apn, c.port.GetName(), c.port.GetBaudrate())
|
||||||
|
|
||||||
|
// Write to file
|
||||||
|
f, err := os.OpenFile("/etc/ppp/peers/"+pppConfigName, os.O_CREATE|os.O_WRONLY, 0666)
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("open ppp config file %w", err)
|
||||||
|
}
|
||||||
|
defer f.Close()
|
||||||
|
if _, err := f.Write([]byte(config)); err != nil {
|
||||||
|
return fmt.Errorf("write to ppp config file: %w", err)
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) setup() error {
|
||||||
|
c.logger.Println("Check requirenments...")
|
||||||
|
if err := c.checkReqs(); err != nil {
|
||||||
|
return fmt.Errorf("check requirenments: %w", err)
|
||||||
|
}
|
||||||
|
// DEBUG show networks and signal
|
||||||
|
resp, err := c.port.Send("AT+COPS?")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("AT+COPS? request: %w", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("DEBUG networks:", resp)
|
||||||
|
|
||||||
|
resp, err = c.port.Send("AT+CSQ")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("AT+CSQ request: %w", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("DEBUG signal quality:", resp)
|
||||||
|
|
||||||
|
// Configure ppp
|
||||||
|
// what is better ASK If /etc/ppp/peers/annalistnet not exists
|
||||||
|
c.logger.Println("Configure ppp...")
|
||||||
|
if err := c.ConfigurePPP(); err != nil {
|
||||||
|
return fmt.Errorf("configure ppp: %w", err)
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) connect() error {
|
||||||
|
resp, err := exec.Command("pon", pppConfigName).Output()
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("execute connect cmd: %w", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("DEBUG pon response:", string(resp))
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) diconnect() error {
|
||||||
|
resp, err := exec.Command("poff", pppConfigName).Output()
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("execute disconnect cmd: %w", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("DEBUG poff response:", string(resp))
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) Init() error {
|
||||||
|
// Setup
|
||||||
|
c.logger.Println("Setup...")
|
||||||
|
if err := c.setup(); err != nil {
|
||||||
|
return fmt.Errorf("setup: %w", err)
|
||||||
|
}
|
||||||
|
// Connect
|
||||||
|
c.logger.Println("Connect...")
|
||||||
|
if err := c.connect(); err != nil {
|
||||||
|
return fmt.Errorf("connect: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
//DEBUG
|
||||||
|
resp, err := exec.Command("ifconfig").Output()
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("execute ifconfig cmd: %w", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("DEBUG ifconfig resp:", string(resp))
|
||||||
|
|
||||||
|
// Test connectin using Ping
|
||||||
|
c.logger.Println("Test...")
|
||||||
|
if !c.Ping() {
|
||||||
|
return fmt.Errorf("ping failed")
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) Ping() bool {
|
||||||
|
// Test - try to connect to Google DNS
|
||||||
|
// ping -I ppp0 8.8.8.8
|
||||||
|
resp, err := exec.Command("ping", "8.8.8.8").Output()
|
||||||
|
if err != nil {
|
||||||
|
c.logger.Println("Ping 1 cmd error:", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("Ping 1 resp:", string(resp))
|
||||||
|
|
||||||
|
resp, err = exec.Command("ping", "-I", "ppp0", "8.8.8.8").Output()
|
||||||
|
if err != nil {
|
||||||
|
c.logger.Println("Ping 2 cmd error:", err)
|
||||||
|
}
|
||||||
|
c.logger.Println("Ping 2 resp:", string(resp))
|
||||||
|
|
||||||
|
return !(strings.Contains(string(resp), "Destination Host Unreachable") || strings.Contains(string(resp), "Destination Net Unreachable")) // tmp solution
|
||||||
|
}
|
||||||
|
|
||||||
|
func (c *conn) Close() error {
|
||||||
|
if err := c.diconnect(); err != nil {
|
||||||
|
return fmt.Errorf("diconnect: %w", err)
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
@ -7,39 +7,61 @@ import (
|
|||||||
"os"
|
"os"
|
||||||
"os/exec"
|
"os/exec"
|
||||||
"strings"
|
"strings"
|
||||||
|
"sync"
|
||||||
"time"
|
"time"
|
||||||
|
|
||||||
"github.com/CGSG-2021-AE4/modem-test/api/modem/at"
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/at"
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/gpio"
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/gps"
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/internet"
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/sms"
|
||||||
)
|
)
|
||||||
|
|
||||||
type ModemData struct {
|
type ModemData struct {
|
||||||
Port string `json:"Port"`
|
Port string `json:"Port"`
|
||||||
GpsData
|
gps.Data
|
||||||
}
|
}
|
||||||
|
|
||||||
type modem struct {
|
type modem struct {
|
||||||
// Internal values
|
// Internal values
|
||||||
logger *log.Logger
|
logger *log.Logger
|
||||||
|
mutex sync.Mutex
|
||||||
|
|
||||||
// Serial values
|
// Serial values
|
||||||
baudrate int
|
baudrate int
|
||||||
|
|
||||||
deviceName string
|
deviceName string
|
||||||
port at.Port
|
port at.Port
|
||||||
|
|
||||||
// Gpio values
|
// Gpio values
|
||||||
onOffPin gpioPin
|
onOffPin gpio.Pin // For turning on and off
|
||||||
|
|
||||||
// Other values
|
// Other values
|
||||||
gpsInfo GpsData
|
|
||||||
lastUpdateTime time.Time
|
lastUpdateTime time.Time
|
||||||
|
|
||||||
|
// GPS
|
||||||
|
gps gps.Gps
|
||||||
|
|
||||||
|
// Internet connection
|
||||||
|
ic internet.Conn
|
||||||
|
|
||||||
|
// Sms and calls
|
||||||
|
sms sms.Sms
|
||||||
}
|
}
|
||||||
|
|
||||||
type Modem interface {
|
type Modem interface {
|
||||||
Init() error
|
Init() error
|
||||||
Validate() bool
|
IsConnected() bool
|
||||||
Update() error
|
Update() error
|
||||||
GetInfo() ModemData
|
GetData() ModemData
|
||||||
|
|
||||||
|
PowerOn() error
|
||||||
|
PowerOff() error
|
||||||
|
|
||||||
|
// Access to SMS, GPS, AT interfaces mostly for debug
|
||||||
|
At() at.Port // Send
|
||||||
|
Gps() gps.Gps // Update, GetData, GetStatus
|
||||||
|
Sms() sms.Sms // Send, ReadNew
|
||||||
|
|
||||||
io.Closer
|
io.Closer
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -47,18 +69,21 @@ func New(logger *log.Logger) Modem {
|
|||||||
return &modem{
|
return &modem{
|
||||||
logger: logger,
|
logger: logger,
|
||||||
baudrate: 115200,
|
baudrate: 115200,
|
||||||
onOffPin: gpioPin{Pin: 6},
|
onOffPin: gpio.New(log.New(logger.Writer(), "gpio", log.LstdFlags), 6),
|
||||||
|
|
||||||
lastUpdateTime: time.Now(),
|
lastUpdateTime: time.Now(),
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) Init() error {
|
func (m *modem) Init() error {
|
||||||
|
m.mutex.Lock()
|
||||||
|
defer m.mutex.Unlock()
|
||||||
|
|
||||||
// Turn module on
|
// Turn module on
|
||||||
// log.Println("=============================== Turn on module")
|
m.logger.Println("=============================== Turn on module")
|
||||||
// if err := m.onOffPin.Init(); err != nil {
|
if err := m.onOffPin.Init(); err != nil {
|
||||||
// return fmt.Errorf("gpio pin init: %w", err)
|
return fmt.Errorf("gpio pin init: %w", err)
|
||||||
// }
|
}
|
||||||
// onOffPin.PowerOn()
|
|
||||||
|
|
||||||
// Search
|
// Search
|
||||||
m.logger.Println("=============================== Search")
|
m.logger.Println("=============================== Search")
|
||||||
@ -82,91 +107,129 @@ func (m *modem) Init() error {
|
|||||||
return fmt.Errorf("connect: %w", err)
|
return fmt.Errorf("connect: %w", err)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Tests
|
// Init submodules
|
||||||
m.logger.Println("=============================== Test")
|
submodulesLogger := m.logger.Writer() // FOR more logs
|
||||||
if err := m.testGPS(); err != nil {
|
// submodulesLogger := io.Discard // FOR less logs
|
||||||
return fmt.Errorf("testGPS: %w", err)
|
|
||||||
}
|
m.logger.Println("=============================== Init submodules")
|
||||||
return nil
|
m.ic = internet.New(log.New(submodulesLogger, "modem-internet : ", log.LstdFlags), m.port)
|
||||||
|
if err := m.ic.Init(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mInternet: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
|
} else {
|
||||||
|
m.logger.Println("\x1b[38;2;0;255;0mInternet OK\x1b[38;2;255;255;255m")
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) Validate() bool {
|
m.sms = sms.New(log.New(submodulesLogger, "modem-sms : ", log.LstdFlags), m.port)
|
||||||
return m.isConnected()
|
if err := m.sms.Init(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mSMS: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
|
} else {
|
||||||
|
m.logger.Println("\x1b[38;2;0;255;0mSMS OK\x1b[38;2;255;255;255m")
|
||||||
|
}
|
||||||
|
|
||||||
|
m.gps = gps.New(log.New(submodulesLogger, "modem-gps : ", log.LstdFlags), m.port)
|
||||||
|
if err := m.gps.Init(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mgps init %w\x1b[38;2;255;255;255m\n", err)
|
||||||
|
} else {
|
||||||
|
m.logger.Println("\x1b[38;2;0;255;0mGPS OK\x1b[38;2;255;255;255m")
|
||||||
|
}
|
||||||
|
|
||||||
|
// Tests
|
||||||
|
// GPS works fine but almost always there is no signal
|
||||||
|
// m.logger.Println("=============================== Test")
|
||||||
|
// if err := m.testGPS(); err != nil {
|
||||||
|
// return fmt.Errorf("testGPS: %w", err)
|
||||||
|
// }
|
||||||
|
|
||||||
|
return nil
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) Update() error {
|
func (m *modem) Update() error {
|
||||||
if !m.isConnected() {
|
m.mutex.Lock()
|
||||||
|
defer m.mutex.Unlock()
|
||||||
|
|
||||||
|
if !m.IsConnected() {
|
||||||
m.logger.Println("No connection to module")
|
m.logger.Println("No connection to module")
|
||||||
return nil
|
return nil
|
||||||
}
|
}
|
||||||
m.logger.Println("Update")
|
m.logger.Println("Update", m.gps)
|
||||||
// ans, err := m.port.Request(at.CmdQuestion, "CGPSINFO")
|
if err := m.gps.Update(); err != nil {
|
||||||
// if err != nil {
|
m.logger.Println("gps update:", err.Error())
|
||||||
// return fmt.Errorf("check GPS info mode: %w", err)
|
}
|
||||||
// }
|
// Read new messages
|
||||||
// ok := ans == "1"
|
|
||||||
// if !ok {
|
|
||||||
// _, err := m.port.Request(at.CmdCheck, "CGPSINFO")
|
|
||||||
// if err != nil {
|
|
||||||
// return fmt.Errorf("switch to GPS info mode: %w", err)
|
|
||||||
// }
|
|
||||||
// m.logger.Println("switched to GPS mode")
|
|
||||||
// } else {
|
|
||||||
// m.logger.Println("mode in right GPS mode")
|
|
||||||
// }
|
|
||||||
|
|
||||||
// Update
|
|
||||||
m.logger.Println("Receiving GPS data...")
|
|
||||||
resp, err := m.port.Send("AT+CGPSINFO")
|
|
||||||
if err != nil {
|
|
||||||
return fmt.Errorf("receive GPS data: %w", err)
|
|
||||||
}
|
|
||||||
if !resp.Check() {
|
|
||||||
return fmt.Errorf("error response")
|
|
||||||
}
|
|
||||||
m.logger.Println("Decoding data...")
|
|
||||||
|
|
||||||
if err := m.gpsInfo.decode(strings.Split(strings.Replace(resp.RmFront("+CGPSINFO:").String(), "\r", "", -1), "\n")[0]); err != nil {
|
|
||||||
m.logger.Println("Gps info decode error:", err.Error())
|
|
||||||
return nil
|
|
||||||
}
|
|
||||||
m.logger.Println("Decoded successfully")
|
|
||||||
return nil
|
return nil
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) GetInfo() ModemData {
|
func (m *modem) GetData() ModemData {
|
||||||
|
m.mutex.Lock()
|
||||||
|
defer m.mutex.Unlock()
|
||||||
|
|
||||||
return ModemData{
|
return ModemData{
|
||||||
Port: m.port.GetName(),
|
Port: m.port.GetName(),
|
||||||
GpsData: m.gpsInfo,
|
Data: m.gps.GetData(),
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) Close() error {
|
func (m *modem) PowerOn() error {
|
||||||
// Not right way I think
|
m.onOffPin.PowerOn() // DEBUG do not want to wait 30 seconds
|
||||||
if err := m.port.Close(); err != nil {
|
|
||||||
return err
|
|
||||||
}
|
|
||||||
if err := m.onOffPin.Close(); err != nil {
|
|
||||||
return err
|
|
||||||
}
|
|
||||||
return nil
|
return nil
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func (m *modem) PowerOff() error {
|
||||||
|
_, err := m.At().Send("AT+CPOF")
|
||||||
|
return err
|
||||||
|
}
|
||||||
|
|
||||||
|
func (m *modem) Sms() sms.Sms {
|
||||||
|
return m.sms
|
||||||
|
}
|
||||||
|
|
||||||
|
func (m *modem) Gps() gps.Gps {
|
||||||
|
return m.gps
|
||||||
|
}
|
||||||
|
|
||||||
|
func (m *modem) At() at.Port {
|
||||||
|
return m.port
|
||||||
|
}
|
||||||
|
|
||||||
|
func (m *modem) Close() error { // I can't return error so I log it
|
||||||
|
m.mutex.Lock()
|
||||||
|
defer m.mutex.Unlock()
|
||||||
|
|
||||||
|
if err := m.sms.Close(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mclose sms error: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
|
}
|
||||||
|
|
||||||
|
if err := m.port.Close(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mclose serial port error: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
|
}
|
||||||
|
if err := m.onOffPin.Close(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mclose gpio pin error: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
|
}
|
||||||
|
if err := m.ic.Close(); err != nil {
|
||||||
|
m.logger.Printf("\x1b[38;2;255;0;0mclose internet connection error: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
|
}
|
||||||
|
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
///////////// Private functions
|
||||||
|
|
||||||
func (m *modem) connect() error {
|
func (m *modem) connect() error {
|
||||||
if !m.Validate() {
|
if m.port == nil {
|
||||||
return fmt.Errorf("port is not defined")
|
return fmt.Errorf("port is not defined")
|
||||||
}
|
}
|
||||||
return m.port.Connect()
|
return m.port.Connect()
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) disconnect() error {
|
func (m *modem) disconnect() error {
|
||||||
if !m.Validate() {
|
if m.port == nil {
|
||||||
return fmt.Errorf("port is not defined")
|
return fmt.Errorf("port is not defined")
|
||||||
}
|
}
|
||||||
return m.port.Disconnect()
|
return m.port.Disconnect()
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) isConnected() bool {
|
func (m *modem) IsConnected() bool {
|
||||||
if m.port != nil {
|
if m.port != nil {
|
||||||
return m.port.IsConnected()
|
return m.port.IsConnected()
|
||||||
}
|
}
|
||||||
@ -176,10 +239,6 @@ func (m *modem) isConnected() bool {
|
|||||||
func (m *modem) testGPS() error {
|
func (m *modem) testGPS() error {
|
||||||
m.logger.Println("Testing GPS")
|
m.logger.Println("Testing GPS")
|
||||||
|
|
||||||
if err := m.switchToGpsMode(); err != nil {
|
|
||||||
return fmt.Errorf("switch to GPS: %w", err)
|
|
||||||
}
|
|
||||||
|
|
||||||
if err := m.Update(); err != nil {
|
if err := m.Update(); err != nil {
|
||||||
return fmt.Errorf("update: %w", err)
|
return fmt.Errorf("update: %w", err)
|
||||||
}
|
}
|
||||||
@ -190,7 +249,8 @@ func (m *modem) testGPS() error {
|
|||||||
|
|
||||||
// Difference: I do not set \n at the end of string
|
// Difference: I do not set \n at the end of string
|
||||||
func (m *modem) getShortInfo() string {
|
func (m *modem) getShortInfo() string {
|
||||||
return fmt.Sprintf("%f,%s,%f,%s", m.gpsInfo.Latitude, m.gpsInfo.LatitudeIndicator, m.gpsInfo.Longitude, m.gpsInfo.LongitudeIndicator)
|
d := m.gps.GetData()
|
||||||
|
return fmt.Sprintf("%f,%s,%f,%s", d.Latitude, d.LatitudeIndicator, d.Longitude, d.LongitudeIndicator)
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) saveGPS(path string) error {
|
func (m *modem) saveGPS(path string) error {
|
||||||
@ -198,7 +258,6 @@ func (m *modem) saveGPS(path string) error {
|
|||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("open file: %w", err)
|
return fmt.Errorf("open file: %w", err)
|
||||||
}
|
}
|
||||||
|
|
||||||
defer f.Close()
|
defer f.Close()
|
||||||
|
|
||||||
if _, err = f.WriteString(m.getShortInfo()); err != nil {
|
if _, err = f.WriteString(m.getShortInfo()); err != nil {
|
||||||
@ -207,6 +266,35 @@ func (m *modem) saveGPS(path string) error {
|
|||||||
return nil
|
return nil
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Short way to send command
|
||||||
|
func (m *modem) printCmd(cmd string) {
|
||||||
|
if resp, err := m.port.Send(cmd); err != nil {
|
||||||
|
m.logger.Println("FAILED TO SEND REQ", cmd, ":", err.Error())
|
||||||
|
} else {
|
||||||
|
_ = resp
|
||||||
|
// m.logger.Println("CMD", cmd, ":", resp)
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Some required commands before checking port
|
||||||
|
func (m *modem) setupPort() error {
|
||||||
|
// Reset input
|
||||||
|
if err := m.port.SerialPort().ResetInputBuffer(); err != nil {
|
||||||
|
return fmt.Errorf("reset input buffer: %w", err)
|
||||||
|
}
|
||||||
|
// Reset output
|
||||||
|
if err := m.port.SerialPort().ResetOutputBuffer(); err != nil {
|
||||||
|
return fmt.Errorf("reset output buffer: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
// These commands ensure that correct modes are set
|
||||||
|
m.printCmd("ATE0") // Sometimes enables echo mode
|
||||||
|
m.printCmd("AT+CGPSFTM=0") // Sometimes does not turn off nmea
|
||||||
|
m.printCmd("AT+CMEE=2") // Turn on errors describtion
|
||||||
|
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
func (m *modem) checkPort(portName string) (outErr error) {
|
func (m *modem) checkPort(portName string) (outErr error) {
|
||||||
defer func() {
|
defer func() {
|
||||||
if outErr != nil { // Clear port if there is error
|
if outErr != nil { // Clear port if there is error
|
||||||
@ -227,22 +315,30 @@ func (m *modem) checkPort(portName string) (outErr error) {
|
|||||||
}
|
}
|
||||||
defer m.port.Disconnect() // Do not bother about errors...
|
defer m.port.Disconnect() // Do not bother about errors...
|
||||||
|
|
||||||
// Ping
|
// To filter dead ports
|
||||||
m.logger.Println("Ping...")
|
if _, err := m.port.Send("AT"); err != nil {
|
||||||
|
|
||||||
if err := m.ping(); err != nil {
|
|
||||||
return fmt.Errorf("ping error: %w", err)
|
return fmt.Errorf("ping error: %w", err)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if err := m.setupPort(); err != nil {
|
||||||
|
return fmt.Errorf("setup port: %w", err)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ping
|
||||||
|
m.logger.Println("Ping...")
|
||||||
|
if err := m.ping(); err != nil {
|
||||||
|
return fmt.Errorf("ping error: %w", err)
|
||||||
|
}
|
||||||
|
m.logger.Println("\x1b[38;2;0;255;0mOK\x1b[38;2;255;255;255m")
|
||||||
|
|
||||||
// Check model
|
// Check model
|
||||||
m.logger.Println("Check model...")
|
m.logger.Println("Check model...")
|
||||||
|
|
||||||
resp, err := m.port.Send("AT+CGMM")
|
resp, err := m.port.Send("AT+CGMM")
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return fmt.Errorf("get model: %w", err)
|
return fmt.Errorf("get model: %w", err)
|
||||||
}
|
}
|
||||||
if !resp.Check() {
|
if !resp.Check() {
|
||||||
return fmt.Errorf("error response: %s", resp)
|
return fmt.Errorf("get model: error response: %s", resp)
|
||||||
}
|
}
|
||||||
model := strings.Split(resp.String(), "\n")[0]
|
model := strings.Split(resp.String(), "\n")[0]
|
||||||
if err != nil {
|
if err != nil {
|
||||||
@ -250,10 +346,10 @@ func (m *modem) checkPort(portName string) (outErr error) {
|
|||||||
}
|
}
|
||||||
rightModel := "SIMCOM_SIM7600E-H"
|
rightModel := "SIMCOM_SIM7600E-H"
|
||||||
// m.logger.Printf("[% x]\n [% x]", []byte("SIMCOM_SIM7600E-H"), []byte(model))
|
// m.logger.Printf("[% x]\n [% x]", []byte("SIMCOM_SIM7600E-H"), []byte(model))
|
||||||
if model[:len(rightModel)] != rightModel {
|
if len(model) >= len(rightModel) && model[:len(rightModel)] != rightModel {
|
||||||
return fmt.Errorf("invalid modem model: %s", model)
|
return fmt.Errorf("invalid modem model: %s", model)
|
||||||
}
|
}
|
||||||
m.logger.Println("Model right")
|
m.logger.Println("\x1b[38;2;0;255;0mOK\x1b[38;2;255;255;255m")
|
||||||
return nil
|
return nil
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -274,7 +370,7 @@ SearchLoop:
|
|||||||
m.logger.Printf("Checking port %s ...\n", p)
|
m.logger.Printf("Checking port %s ...\n", p)
|
||||||
|
|
||||||
if err := m.checkPort("/dev/" + p); err != nil {
|
if err := m.checkPort("/dev/" + p); err != nil {
|
||||||
m.logger.Printf("Check failed: %s\n", err.Error())
|
m.logger.Printf("\x1b[38;2;255;0;0mCheck failed: %s\x1b[38;2;255;255;255m\n", err.Error())
|
||||||
continue SearchLoop
|
continue SearchLoop
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -288,48 +384,14 @@ SearchLoop:
|
|||||||
func (m *modem) ping() error {
|
func (m *modem) ping() error {
|
||||||
resp, err := m.port.Send("AT")
|
resp, err := m.port.Send("AT")
|
||||||
if err != nil {
|
if err != nil {
|
||||||
return err
|
return fmt.Errorf("AT request: %w", err)
|
||||||
}
|
}
|
||||||
if !resp.Check() {
|
if !resp.Check() {
|
||||||
return fmt.Errorf("connection lost")
|
return fmt.Errorf("AT request: error response: %s", resp)
|
||||||
}
|
}
|
||||||
return nil
|
return nil
|
||||||
}
|
}
|
||||||
|
|
||||||
func (m *modem) switchToGpsMode() error {
|
|
||||||
m.logger.Println("Enabling GPS mode...")
|
|
||||||
// Reset intput
|
|
||||||
if err := m.port.GetSerialPort().ResetInputBuffer(); err != nil {
|
|
||||||
return fmt.Errorf("reset input buffer: %w", err)
|
|
||||||
}
|
|
||||||
|
|
||||||
// Check gps mode status
|
|
||||||
resp, err := m.port.Send("AT+CGPS?")
|
|
||||||
if err != nil {
|
|
||||||
return fmt.Errorf("make at ask: %w", err)
|
|
||||||
}
|
|
||||||
if !resp.Check() {
|
|
||||||
return fmt.Errorf("error response")
|
|
||||||
}
|
|
||||||
ans := strings.Replace(strings.Split(strings.Split(resp.RmFront("+CGPS:").String(), "\n")[0], ",")[0], " ", "", -1)
|
|
||||||
if ans == "1" {
|
|
||||||
m.logger.Println("GPS already enabled")
|
|
||||||
return nil
|
|
||||||
}
|
|
||||||
m.logger.Println(ans)
|
|
||||||
|
|
||||||
// Modem is not in GPS mode
|
|
||||||
resp, err = m.port.Send("AT+CGPS=1")
|
|
||||||
if err != nil {
|
|
||||||
return fmt.Errorf("try to switch to gps: %w", err)
|
|
||||||
}
|
|
||||||
if !resp.Check() {
|
|
||||||
return fmt.Errorf("switch tp GPS failed")
|
|
||||||
}
|
|
||||||
m.logger.Println("GPS mode enabled")
|
|
||||||
return nil
|
|
||||||
}
|
|
||||||
|
|
||||||
func getTtyDevices() ([]string, error) {
|
func getTtyDevices() ([]string, error) {
|
||||||
// Get ports
|
// Get ports
|
||||||
/**/
|
/**/
|
||||||
|
69
api/modem/sms/errors.go
Normal file
69
api/modem/sms/errors.go
Normal file
@ -0,0 +1,69 @@
|
|||||||
|
package sms
|
||||||
|
|
||||||
|
import (
|
||||||
|
"fmt"
|
||||||
|
"strconv"
|
||||||
|
)
|
||||||
|
|
||||||
|
func DecodeError(code int) string {
|
||||||
|
switch code {
|
||||||
|
case 300:
|
||||||
|
return "ME failure"
|
||||||
|
case 301:
|
||||||
|
return "SMS service of ME reserved"
|
||||||
|
case 302:
|
||||||
|
return "Operation not allowed"
|
||||||
|
case 303:
|
||||||
|
return "Operation not supported"
|
||||||
|
case 304:
|
||||||
|
return "Invalid PDU mode parameter"
|
||||||
|
case 305:
|
||||||
|
return "Invalid text mode parameter"
|
||||||
|
case 310:
|
||||||
|
return "SIM not inserted"
|
||||||
|
case 311:
|
||||||
|
return "SIM PIN required"
|
||||||
|
case 312:
|
||||||
|
return "PH-SIM PIN required"
|
||||||
|
case 313:
|
||||||
|
return "SIM failure"
|
||||||
|
case 314:
|
||||||
|
return "SIM busy"
|
||||||
|
case 315:
|
||||||
|
return "SIM wrong"
|
||||||
|
case 316:
|
||||||
|
return "SIM PUK required"
|
||||||
|
case 317:
|
||||||
|
return "SIM PIN2 required"
|
||||||
|
case 318:
|
||||||
|
return "SIM PUK2 required"
|
||||||
|
case 320:
|
||||||
|
return "Memory failure"
|
||||||
|
case 321:
|
||||||
|
return "Invalid memory index"
|
||||||
|
case 322:
|
||||||
|
return "Memory full"
|
||||||
|
case 330:
|
||||||
|
return "SMSC address unknown"
|
||||||
|
case 331:
|
||||||
|
return "No network service"
|
||||||
|
case 332:
|
||||||
|
return "Network timeout"
|
||||||
|
case 340:
|
||||||
|
return "NO +CNMA ACK EXPECTED"
|
||||||
|
case 341:
|
||||||
|
return "Buffer overflow"
|
||||||
|
case 342:
|
||||||
|
return "SMS size more than expected"
|
||||||
|
case 500:
|
||||||
|
return "Unknown error"
|
||||||
|
}
|
||||||
|
return "UNDEFINED ERROR CODE"
|
||||||
|
}
|
||||||
|
|
||||||
|
func GetError(msg []byte) (int, error) {
|
||||||
|
if len(msg) >= len("+CMS ERROR: ")+3 && string(msg[:len("+CMS ERROR: ")]) == "+CMS ERROR: " {
|
||||||
|
return strconv.Atoi(string(msg[len("+CMS ERROR: ") : len("+CMS ERROR: ")+3]))
|
||||||
|
}
|
||||||
|
return 0, fmt.Errorf("failed to parse error")
|
||||||
|
}
|
99
api/modem/sms/sms.go
Normal file
99
api/modem/sms/sms.go
Normal file
@ -0,0 +1,99 @@
|
|||||||
|
package sms
|
||||||
|
|
||||||
|
import (
|
||||||
|
"fmt"
|
||||||
|
"io"
|
||||||
|
"log"
|
||||||
|
"strings"
|
||||||
|
|
||||||
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem/at"
|
||||||
|
)
|
||||||
|
|
||||||
|
type dialer struct {
|
||||||
|
logger *log.Logger
|
||||||
|
port at.Port
|
||||||
|
}
|
||||||
|
|
||||||
|
type Sms interface {
|
||||||
|
Init() error
|
||||||
|
Send(number, msg string) error // Send sms
|
||||||
|
ReadNew() ([]string, error) // Read new smses
|
||||||
|
|
||||||
|
io.Closer
|
||||||
|
}
|
||||||
|
|
||||||
|
func New(logger *log.Logger, port at.Port) Sms {
|
||||||
|
return &dialer{
|
||||||
|
logger: logger,
|
||||||
|
port: port,
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
func (d *dialer) Init() error {
|
||||||
|
// Ensure serial port
|
||||||
|
if !d.port.IsConnected() {
|
||||||
|
return fmt.Errorf("serial port is not connected")
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check SIM an PIN
|
||||||
|
if resp, err := d.port.Send("AT+CPIN?"); err != nil || !resp.Check() {
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("check pin: %w", err)
|
||||||
|
}
|
||||||
|
return fmt.Errorf("check pin: error response: %s", resp)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ensure text format
|
||||||
|
d.logger.Println(d.port.Send("AT+CMGF"))
|
||||||
|
if resp, err := d.port.Send("AT+CMGF=1"); err != nil || !resp.Check() {
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("set to text format request: %w", err)
|
||||||
|
}
|
||||||
|
return fmt.Errorf("set SIM format: error response: %s", resp)
|
||||||
|
}
|
||||||
|
return nil
|
||||||
|
}
|
||||||
|
|
||||||
|
func (d *dialer) Send(number, msg string) error {
|
||||||
|
d.port.Send(fmt.Sprintf(`AT+CMGS="%s"`, number)) // Because it will throw error
|
||||||
|
resp, err := d.port.RawSend(fmt.Sprintf("%s\n\r", msg)) // Add additional \r\n because there is not supposed to be
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("message request: %w", err)
|
||||||
|
}
|
||||||
|
d.logger.Println("SEND RESPONSE:", resp)
|
||||||
|
resp, err = d.port.RawSend("\x1A")
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("message request: %w", err)
|
||||||
|
}
|
||||||
|
d.logger.Println("SEND RESPONSE:", resp)
|
||||||
|
errCode, err := GetError([]byte(resp))
|
||||||
|
if err != nil {
|
||||||
|
return fmt.Errorf("send sms failed and failed to get error: %w", err)
|
||||||
|
}
|
||||||
|
return fmt.Errorf("failed to send with SMS error: %d - %s", errCode, DecodeError(errCode))
|
||||||
|
}
|
||||||
|
|
||||||
|
// Reads all new messages
|
||||||
|
func (d *dialer) ReadNew() ([]string, error) {
|
||||||
|
resp, err := d.port.Send("AT+CMGL=\"UNREAD\"")
|
||||||
|
if err != nil {
|
||||||
|
return nil, fmt.Errorf("AT+CMGL request: %w", err)
|
||||||
|
}
|
||||||
|
msgs := strings.Split(strings.Replace(string(resp), "\r", "", -1), "\n")
|
||||||
|
|
||||||
|
outMsgs := make([]string, 0)
|
||||||
|
for _, s := range msgs {
|
||||||
|
if len(s) >= len("+CMGL:") && s[:len("+CMGL:")] == "+CMGL:" {
|
||||||
|
params := strings.Split(s[len("+CMGL:"):], ",")
|
||||||
|
d.logger.Println("GET MSG:", params)
|
||||||
|
} else {
|
||||||
|
outMsgs = append(outMsgs, s)
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return outMsgs, nil // TODO
|
||||||
|
}
|
||||||
|
|
||||||
|
func (d *dialer) Close() error {
|
||||||
|
return nil
|
||||||
|
}
|
2
go.mod
2
go.mod
@ -1,4 +1,4 @@
|
|||||||
module github.com/CGSG-2021-AE4/modem-test
|
module gitea.unprism.ru/KRBL/sim-modem
|
||||||
|
|
||||||
go 1.22.5
|
go 1.22.5
|
||||||
|
|
||||||
|
43
main.go
43
main.go
@ -4,7 +4,7 @@ import (
|
|||||||
"log"
|
"log"
|
||||||
"os"
|
"os"
|
||||||
|
|
||||||
"github.com/CGSG-2021-AE4/modem-test/api/modem"
|
"gitea.unprism.ru/KRBL/sim-modem/api/modem"
|
||||||
)
|
)
|
||||||
|
|
||||||
func main() {
|
func main() {
|
||||||
@ -16,15 +16,46 @@ func main() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
func mainE() error {
|
func mainE() error {
|
||||||
m := modem.New(log.New(os.Stdout, "modem:", log.LstdFlags))
|
logger := log.New(os.Stdout, "main : ", log.LstdFlags)
|
||||||
|
m := modem.New(log.New(logger.Writer(), "modem : ", log.LstdFlags))
|
||||||
|
logger.Println("||||||||||||||||| INIT |||||||||||||||")
|
||||||
|
if err := m.Init(); err != nil {
|
||||||
|
logger.Println("Init ended with error:", err.Error())
|
||||||
|
logger.Println("Try to turn on")
|
||||||
|
if err := m.PowerOn(); err != nil {
|
||||||
|
return err
|
||||||
|
}
|
||||||
|
logger.Println("Reinit")
|
||||||
if err := m.Init(); err != nil {
|
if err := m.Init(); err != nil {
|
||||||
return err
|
return err
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
if !m.IsConnected() {
|
||||||
|
logger.Println("AAAAAAAAAAAAAAA Modem is not connected")
|
||||||
return nil
|
return nil
|
||||||
// ports, err := serial.GetPortsList()
|
}
|
||||||
// if err != nil {
|
logger.Println("||||||||||||||||| GET INFO |||||||||||||||||")
|
||||||
|
logger.Println(m.Update())
|
||||||
|
logger.Printf("DATA: %+v\n", m.GetData())
|
||||||
|
|
||||||
|
logger.Println("||||||||||||||||| SEND SMS |||||||||||||||||")
|
||||||
|
logger.Println(m.At().Send("AT+CNUM"))
|
||||||
|
// if err := m.Sms().Send("+79218937173", "CGSG forever"); err != nil {
|
||||||
// return err
|
// return err
|
||||||
// }
|
// }
|
||||||
// log.Println(ports)
|
if ms, err := m.Sms().ReadNew(); err != nil {
|
||||||
// return nil
|
return err
|
||||||
|
} else {
|
||||||
|
logger.Println("NEW:", ms)
|
||||||
|
}
|
||||||
|
logger.Println("||||||||||||||||| Checking gps status |||||||||||||||||")
|
||||||
|
st, err := m.Gps().GetStatus()
|
||||||
|
if err != nil {
|
||||||
|
return err
|
||||||
|
}
|
||||||
|
logger.Printf("GPS Status:%+v\n", st)
|
||||||
|
|
||||||
|
// logger.Println("Turn off", m.PowerOff())
|
||||||
|
|
||||||
|
return nil
|
||||||
}
|
}
|
||||||
|
Reference in New Issue
Block a user