geolink / opentracker

OpenTracker - open source GPS/GLONASS hardware
GNU General Public License v2.0
163 stars 68 forks source link

Can not connect to remote server: updates.geolink.io Modem Reply: +CEER: "No report available" Modem Reply: +CME ERROR: 4 #72

Closed Codematic closed 7 years ago

Codematic commented 7 years ago

I have serious problems to program OpenTracker. I have tried several source codes (3.1.1, 3.1.2 and 3.1.3) but non of those seems to work properly. Also tried to consider to have correct board support package for each of those source code packages (1.0.3 vs. 1.0.4). But that did not help either. Hope some of you have quick solution to this issue.

The board should be 3G version (HW rev 2.4C). img_6184_small

To make sure, I have used this setup with factory firmware more than 2 months and also same power supply were just fine for couple of hours with factory firmware. img_6185_small

Could there be something I have missed while creating tracker.h? (something to define more?)

Also same SIM card is used before without problems.

Is there something else I could try to modify to sort out this issue?

Btw, should all of those source code packages work with this board?

Here is log of issues with the 3.1.2 package:

setup() started
settings_load() started
settings_load(): First run flag:
255
settings_load(): setting defaults from config
settings_load(): set config.interval:
10000
internet
settings_save() started
settings_save() finished
settings_load(): config.interval:
10000
settings_load(): config.interval_send:
1
settings_load(): config.powersave:
0
settings_load() finished
store_get_index() started
store_get_index(): Not found, initialize log position:
1024
store_get_index() ended
gps_setup() started
gps_on() started
gps_on() completed
$PMTK011,MTKGPS*08
$PMTK010,001*2E
$PMTK011,MTKGPS*08
$PMTK010,002*2D
gps_setup() completed
gsm_setup() started
gsm_off() started
gsm_off() finished
gsm_on() started
gsm_send_at() started
gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
Modem Reply:

RDY

gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
1
gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
2
gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
3
gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
4
gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
Modem Reply:

Modem Reply:
OK

Modem Reply:

Modem Reply:
OK

gsm_on() finished
gsm_set_pin() started
Modem Reply:

Modem Reply:
+CPIN: READY

Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Warning: timed out waiting for last modem reply
Modem Reply:

Modem Reply:
+CPIN: READY

Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Warning: timed out waiting for last modem reply
Modem Reply:

Modem Reply:
+CPIN: READY

Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Warning: timed out waiting for last modem reply
Modem Reply:

Modem Reply:
+CPIN: READY

Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Warning: timed out waiting for last modem reply
Modem Reply:

Modem Reply:
+CPIN: READY

Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Warning: timed out waiting for last modem reply
gsm_set_pin() completed
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_imei() started
Modem Reply:

865789021843729

OK

gsm_get_imei() result:
B
gsm_get_imei() completed
gsm_startup_cmd() started
Modem Reply:

Modem Reply:
OK

Modem Reply:

Modem Reply:
+CME ERROR: 4

Modem Reply:

Modem Reply:
OK

gsm_startup_cmd() completed
gsm_set_apn() started
Modem Reply:

Modem Reply:
ERROR

Modem Reply:

Modem Reply:
+CME ERROR: 4

Modem Reply:

Modem Reply:
ERROR

Modem Reply:

Modem Reply:
+CME ERROR: 4

Modem Reply:

Modem Reply:
ERROR

Modem Reply:

gsm_send_at() started
Modem Reply:
+CME ERROR: 4

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_set_apn() completed
gsm_setup() completed
setup() completed
sms_check() started
Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Deleting READ and SENT SMS
Modem Reply:

Modem Reply:
ERROR

Modem Reply:

Modem Reply:
ERROR

sms_check() completed
Ignition status:
0
Ignition is ON!
collect_all_data() started
gsm_get_time() started
Modem Reply:

+CCLK: "17/08/21,19:37:00+12"

OK

gsm_get_time() result:
17/08/21,19:37:00+12
gsm_get_time() completed
$GNRMC,193343.426,A,6110.8872,N,02141.2018,E,0.33,345.45,210817,,,A*7F
Invalid altitude, retrying.

$GPVTG,345.45,T,,M,0.33,N,0.61,K,A*39
$GPGGA,193343.426,6110.8872,N,02141.2018,E,1,5,4.40,32.0,M,21.1,M,,*6B4,272,31,87,27,340,,69,23,101,,85,05,225,*6F
$GLGSV,3,3,09,73,02,168,*55
1,11,037,33,44,11,132,,29,09,006,28*79
$GLGSV,3,1,09,70,81,085,,71,43,286,28,79,41,044,25,80,41,134,22*6D
$GLGSV,3,2,09,86,33,271,28,87,28,338,38,69,22,102,17,85,04,225,*6D
$GLGSV,3,3,09,73,03,168,18*5D
$GNGLL,6110.8417,N,02141.1700,E,193700.000,A,A*47
$GNRMC,193701.000,A,6110.8417,N,02141.1700,E,0.00,351.76,210817,,,A*7A
Invalid altitude, retrying.

$GPVTG,351.76,T,,M,0.00,N,0.00,K,A*3B
$GPGGA,193701.000,6110.8417,N,02141.1700,E,1,15,0.71,34.0,M,21.1,M,,*5A
GPS fix received.
Data is current.
Current time set from GPS time:
17/08/21,19:37:01+00
gsm_set_time() started
Modem Reply:

Modem Reply:
OK

gsm_set_time() completed

GPS already available, breaking
collect_gps_data(): fix acquired
Failed checksums:
3
collect_all_data() completed
Current:
17/08/21,19:37:00+12[210817,19370100,61.180695,21.686167,0.00,34.00,351.76,71,15]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
Can not send data, saving to flash memory
storage_save_current() started
storage_save_current() ended
storage_send_logs() started
storage_send_logs(): Found log sent position:
1024
storage_send_logs(): Sending data from:
1024
Log data:
17/08/21,19:37:00+12[210817,19370100,61.180695,21.686167,0.00,34.00,351.76,71,15]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
storage_send_logs(): Error sending logs
storage_send_logs() ended
Sleeping for:
-118040
ms
Error: negative sleep time.
sms_check() started
Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Deleting READ and SENT SMS
Modem Reply:

Modem Reply:
ERROR

Modem Reply:

Modem Reply:
ERROR

sms_check() completed
Ignition status:
0
Ignition is ON!
collect_all_data() started
gsm_get_time() started
Modem Reply:

+CCLK: "17/08/21,19:39:08+00"

OK

gsm_get_time() result:
17/08/21,19:39:08+00
gsm_get_time() completed
$GNGSA,A,3,03,06,26,22,31,02,29,23,09,,,,1.08,0.71,0.81*18
$GNGSA,A,3,69,87,71,79,80,86,,,,,,,1.08,0.71,0.81*14
$GPGSV,3,1,12,23,75,122,31,09,65,228,39,06,47,258,33,03,34,133,23*7E
$GPGSV,3,2,12,02,28,312,25,26,23,070,31,07,14,189,16,16,13,098,19*7D
G42,133,18,79,41,043,20*6D
$GLGSV,3,2,10,86,32,270,36,87,28,337,39,69,21,102,,73,05,168,*63
$GLGSV,3,3,10,85,03,225,,88,01,014,*6B
$GNGLL,6110.8417,N,02141.1700,E,193908.000,A,A*41
$GNRMC,193909.000,A,6110.8417,N,02141.1700,E,0.00,351.76,210817,,,A*7C
GPS fix received.
Data is current.
Current time set from GPS time:
17/08/21,19:39:09+00
gsm_set_time() started
Modem Reply:

Modem Reply:
OK

gsm_set_time() completed

GPS already available, breaking
collect_gps_data(): fix acquired
Failed checksums:
4
collect_all_data() completed
Current:
17/08/21,19:39:08+00[210817,19390900,61.180695,21.686167,0.00,34.00,351.76,71,15]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
Can not send data, saving to flash memory
storage_save_current() started
storage_save_current() ended
storage_send_logs() started
storage_send_logs(): Found log sent position:
1024
storage_send_logs(): Sending data from:
1024
Log data:
17/08/21,19:37:00+12[210817,19370100,61.180695,21.686167,0.00,34.00,351.76,71,15]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
storage_send_logs(): Error sending logs
storage_send_logs() ended
Sleeping for:
-117842
ms
Error: negative sleep time.
sms_check() started
Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Deleting READ and SENT SMS
Modem Reply:

Modem Reply:
ERROR

Modem Reply:

Modem Reply:
ERROR

sms_check() completed
Ignition status:
0
Ignition is ON!
collect_all_data() started
gsm_get_time() started
Modem Reply:

+CCLK: "17/08/21,19:41:16+00"

OK

gsm_get_time() result:
17/08/21,19:41:16+00
gsm_get_time() completed
$GPVTG,351.76,T,,M,0.00,N,0.00,K,A*3B
$GPGGA,193909.000,6110.8417,N,02141.1700,E,1,14,0.73,34.0,M,21.1,M,,*5F
GPS fix received.
Warning: this fix date/time already logged, retrying

$GNGSA,A,3,03,06,26,22,31,02,29,23,09,,,,1.08,0.73,0.80*1B
$GNGSA,A,3,87,71,79,80,86,,,,,,,,1.08,0.73,0.80*18
$GPGSV,3,1,12,23,75,121,29,09,026,24,068,33,16,15,097,20,07,15,189,22*76
$GPGSV,3,3,12,29,10,005,32,22,10,130,24,31,10,037,26,49,,,*4F
$GLGSV,3,1,10,70,78,091,,71,45,287,35,80,43,132,21,79,40,042,21*69
$GLGSV,3,2,10,86,31,269,39,87,28,337,38,69,20,103,,73,06,167,*6A
$GLGSV,3,3,10,85,02,225,,88,01,014,*6A
$GNGLL,6110.8417,N,02141.1700,E,194116.000,A,A*41
$GNRMC,194117.000,A,6110.8417,N,02141.1700,E,0.00,351.76,210817,,,A*7C
GPS fix received.
Data is current.
Current time set from GPS time:
17/08/21,19:41:17+00
gsm_set_time() started
Modem Reply:

Modem Reply:
OK

gsm_set_time() completed

GPS already available, breaking
collect_gps_data(): fix acquired
Failed checksums:
5
collect_all_data() completed
Current:
17/08/21,19:41:16+00[210817,19411700,61.180695,21.686167,0.00,34.00,351.76,73,14]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
Can not send data, saving to flash memory
storage_save_current() started
storage_save_current() ended
storage_send_logs() started
storage_send_logs(): Found log sent position:
1024
storage_send_logs(): Sending data from:
1024
Log data:
17/08/21,19:37:00+12[210817,19370100,61.180695,21.686167,0.00,34.00,351.76,71,15]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
storage_send_logs(): Error sending logs
storage_send_logs() ended
Sleeping for:
-117950
ms
Error: negative sleep time.
sms_check() started
Modem Reply:

Modem Reply:
OK

Warning: timed out waiting for last modem reply
Deleting READ and SENT SMS
Modem Reply:

Modem Reply:
ERROR

Modem Reply:

Modem Reply:
ERROR

sms_check() completed
Ignition status:
0
Ignition is ON!
collect_all_data() started
gsm_get_time() started
Modem Reply:

+CCLK: "17/08/21,19:43:24+00"

OK

gsm_get_time() result:
17/08/21,19:43:24+00
gsm_get_time() completed
$GPVTG,351.76,T,,M,0.00,N,0.00,K,A*3B
$GPGGA,194117.000,6110.8417,N,02141.1700,E,1,14,0.78,34.0,M,21.1,M,,*54
GPS fix received.
Warning: this fix date/time already logged, retrying

$GNGSA,A,3,03,06,26,22,31,02,29,23,09,,,,1.52,0.78,1.31*14
$GNGSA,A,3,87,71,79,80,86,,,,,,,,1.52,0.78,1.31*17
$GPGSV,3,1,12,23,74,118,35,09,0,28*7A
$GPGSV,3,2,12,02,30,310,38,26,24,067,33,07,16,189,20,16,15,096,27*7B
$GPGSV,3,3,12,29,10,004,32,22,09,130,14,31,09,036,18,51,,,*48
$GLGSV,3,1,10,70,77,092,22,71,46,288,36,80,44,131,19,79,39,041,23*6A
$GLGSV,3,2,10,86,31,268,38,87,29,335,31,69,19,103,17,73,06,167,*6C
$GLGSV,3,3,10,88,02,014,,85,01,224,*6B
$GNGLL,6110.8417,N,02141.1700,E,194324.000,A,A*42
$GNRMC,194325.000,A,6110.8417,N,02141.1700,E,0.00,351.76,210817,,,A*7F
GPS fix received.
Data is current.
Current time set from GPS time:
17/08/21,19:43:25+00
gsm_set_time() started
Modem Reply:

Modem Reply:
OK

gsm_set_time() completed

GPS already available, breaking
collect_gps_data(): fix acquired
Failed checksums:
6
collect_all_data() completed
Current:
17/08/21,19:43:24+00[210817,19432500,61.180695,21.686167,0.00,34.00,351.76,78,14]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
Can not send data, saving to flash memory
storage_save_current() started
storage_save_current() ended
storage_send_logs() started
storage_send_logs(): Found log sent position:
1024
storage_send_logs(): Sending data from:
1024
Log data:
17/08/21,19:37:00+12[210817,19370100,61.180695,21.686167,0.00,34.00,351.76,71,15]

gsm_send_at() started
Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

Modem Reply:

OK

gsm_send_at() completed
0
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
0
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
1
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() started
Modem Reply:

Modem Reply:
+CPAS: 0

Modem Reply:

Modem Reply:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Reply:

Modem Reply:
+CME ERROR: 4

gsm_get_connection_status() returned:
-1
Modem Reply:

Modem Reply:
ERROR

Connecting to remote server...
2
Modem Reply:

Modem Reply:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Reply:

Modem Reply:
+CEER: "No report available"

Modem Reply:

Modem Reply:
OK

gsm_connect() completed
gsm_disconnect() started
Modem Reply:

Modem Reply:
ERROR

gsm_disconnect() completed
Error, can not send data or no connection.
storage_send_logs(): Error sending logs
storage_send_logs() ended
Sleeping for:
-118036
ms
Error: negative sleep time.
sms_check() started
Modem Reply:

Modem Reply:
OK

tracker.h:

#define ADDON_INTERFACE 0     //non-zero if you have custom addon implementation

//OpenTracker config
#define DEBUG 1               //debug console (0=disabled, 1=send diangostic messages, 2=also accept test commands)

#define ALWAYS_ON 0           //set to 1 to make the tracker log even with the ignition off

//default settings (can be overwritten and stored in EEPRom)
#define INTERVAL 10000        //how often to collect data (milli sec, 600000 - 10 mins)
#define INTERVAL_SEND 1       //how many times to collect data before sending (times), sending interval interval*interval_send (4 default)
#define POWERSAVE 0           //enable powersaving (turn off modem, gps on every loop)
#define KEY "cSQ88qShwC3"     //key for connection, will be sent with every data transmission - max 12 chars
#define DATA_LIMIT 2500       //current data limit, data collected before sending to remote server can not exceed this
#define SMS_KEY "pass"        //default password for SMS auth
#define SIM_PIN ""            //default SIM PIN (none)

#define SMS_DONT_CHECK_WITH_ENGINE_RUNNING 0 // 1=disable sms commands when the engine is running
#define SMS_CHECK_INCLUDE_IMEI  0           // 0=check only password, 1=also check IMEI (format: #pass@imei,command=value)

#define LOCATE_COMMAND_FORMAT_IOS 1         // 1=google maps links will be sent as comgooglemaps://, 0=use format https://maps.google...

#define GSM_MODEM_COMMAND_TIMEOUT 10
#define GSM_SEND_FAILURES_REBOOT 30         // 0=disabled, increase to set the number of GSM data send failures that will trigger a reboot of the opentracker device
#define GSM_REPLY_FAILURES_REBOOT 10        // 0=disabled, increase to set the number of GSM reply failures that will trigger a reboot of the opentracker device
#define GSM_DISCONNECT_AFTER_SEND 0         // 0=keep modem data session active, only close TCP connection (default), 1=close data session after each send

#define GPS_COLLECT_TIMEOUT       4         // max time spent looking for a GPS fix (seconds)

#define ENGINE_RUNNING_LOG_FAST_AS_POSSIBLE 0 // 1=when the engine is running send interval is ignored

#define SEND_RAW 0                          // enable to use the new raw tcp send method to minimise data use
#define SEND_RAW_INCLUDE_IMEI 1
#define SEND_RAW_INCLUDE_KEY 1
#define SEND_RAW_INCLUDE_TIMESTAMP 0

#define DATA_INCLUDE_GPS_DATE 1             // enable to include the GPS date in the POST string
#define DATA_INCLUDE_GPS_TIME 1             // enable to include the GPS time in the POST string
#define DATA_INCLUDE_LATITUDE 1             // enable to include latitude
#define DATA_INCLUDE_LONGITUDE 1            // enable to include longitude
#define DATA_INCLUDE_SPEED 1                // enable to include speed (km/h)
#define DATA_INCLUDE_ALTITUDE 1             // enable to include altitude
#define DATA_INCLUDE_HEADING 1              // enable to include heading
#define DATA_INCLUDE_HDOP 1                 // enable to include hdop
#define DATA_INCLUDE_SATELLITES 1           // enable to include satellites
#define DATA_INCLUDE_BATTERY_LEVEL 0        // enable to include the battery level in the POST string
#define DATA_INCLUDE_IGNITION_STATE 0       // enable to include the ignition state in the POST string
#define DATA_INCLUDE_ENGINE_RUNNING_TIME 0  // enable to include the engine running time (in seconds) in the POST string

#define PARSE_IGNORE_EOF 0        // 0=consider transmission successful if "eof" included in response body (default)
#define PARSE_IGNORE_COMMANDS 0   // 0=parse commands included in response body (default)
// define this macro to accept only certain HTTP response codes (default is any)
//#define PARSE_ACCEPTED_RESPONSE_CODES RESP_CODE(200)

#define HTTP_USER_AGENT "OpenTracker 3.1"
//#define HTTP_USE_GET                      // leave commented for POST, uncomment for GET request

#define HTTP_PARAM_IMEI "imei"
#define HTTP_PARAM_KEY  "key"
#define HTTP_PARAM_DATA "d"

#define PROTO "TCP"
#define HOSTNAME "updates.geolink.io"
#define HTTP_PORT "80"
#define URL "/index.php"

#define DEFAULT_APN   "internet"      //default APN
#define DEFAULT_USER  ""              //default APN user
#define DEFAULT_PASS  ""              //default APN pass

#define DEFAULT_ALARM_ON   0          //if active SMS will be sent on Ignition ON/OFF
#define DEFAULT_ALARM_SMS  ""         //default SMS text for alarm

#define PACKET_SIZE 1400              //TCP data chunk size, modem accept max 1460 bytes per send
#define PACKET_SIZE_DELIVERY 3000     //in case modem has this number of bytes undelivered, wait till sending new data (3000 bytes default, max sending TCP buffer is 7300)

#define CONNECT_RETRY 3               //how many times to retry connecting to remote server
#define CONNECT_TIMEOUT 15000         //how much time to wait for each connection attempt

#define STORAGE 1                     //save logs in flash storage
#define STORAGE_FIRST_RUN_PAGE 0      //flash index to store flag for first run - very first page
#define STORAGE_CONFIG_PAGE 1         //flash index to store configuration - just after FIRST_RUN page
#define STORAGE_CONFIG_ADDON 512      //flash index to store addon configuration
#define STORAGE_DATA_START 1024       //starting flash index to store logs (first bytes reserved for configuration)
#define STORAGE_DATA_END 131071       //the last possible flash index (max 131072, one last byte must be reserved for marker)
//#define STORAGE_DATA_END 2048       //the last possible flash index (max 131072, one last byte must be reserved for marker)

#define STORAGE_MAX_SEND_OLD  5       //maximum number of old data to send from log

// List of APN configurations to scan at power-on/reset
// (undefine to use the default APN only)
//#define KNOWN_APN_LIST \
  //KNOWN_APN("example.apn", "user", "pass", "ISP name", NULL) \
  //RECORD FORMAT (ISP and NULL are not used) - INSERT ABOVE
  //KNOWN_APN("APN", "USERNAME", "PASSWORD", "ISP", NULL) \

#define KNOWN_APN_SCAN_MODE 1       // 0=check GPRS context only, 2=attempt only server connection, 1=use both in sequence
#define KNOWN_APN_SCAN_USE_RESET 0  // 1=reset modem to change APN, 0=change APN without reset
ppescher commented 7 years ago

Looking at your log I can see the modem is working, but AT command echo has been turned off.

Recent firmware versions perform auto-baudrate using the "ATE1" command string, that should turn command echo back on, see for instance: https://github.com/geolink/opentracker/blob/55f2d320504bc305fd885f1ff1d5d4da5c12f680/OpenTracker/gsm.ino#L381

However, in your log the modem reply is only "OK", without command echo. Please check that your firmware does send the "ATE1" command, because old versions only used "AT".

Codematic commented 7 years ago

Thank you for your prompt reply.

I investigated the gsm.ino files I tried with no luck and none of them put the echo on (ATE1).

After realising this I cloned the latest repository where that is on and found out that "RDY" is replied back to cpu from modem. According to "Quectel_WCDMA_UGxx_AT_Commands_Manual_V1.7.pdf" it is not right (should return OK or ATE1).

This is very strange since I managed to run the OpenTracker with original software without any problems (I even took a log for that and there seems to be ATE1 coming back properly).

With this issue, I even tried an other power source, but this is now something else than power source issue. (In other words: No help from that change.)

Please see the log with the latest code from the up to date repository:

setup() started
settings_load() started
settings_load(): First run flag:
1
settings_load(): no a first run, loading settings.
settings_load(): config.interval:
5000
settings_load(): config.interval_send:
4
settings_load(): config.powersave:
1
settings_load(): config.debug:
1
settings_load(): config.queclocator:
0
settings_load() finished
store_get_index() started
store_get_index(): Not found, initialize log position:
1024
store_get_index() ended
gps_setup() started
gps_on() started
gps_on() completed
$PMTK011,MTKGPS*08
$PMTK010,001*2E
$PMTK011,MTKGPS*08
$PMTK010,002*2D
gps_setup() completed
gsm_setup() started
gsm_off() started
gsm_off() finished
gsm_on() started
gsm_send_at() started
gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
Modem Reply:

RDY

gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
1
gsm_send_at() started
gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
Modem Reply:

RDY

gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
2
gsm_send_at() started
gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
Modem Reply:

RDY

gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
3
gsm_send_at() started
gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
gsm_off() started
Modem Reply:

RDY

gsm_off() finished
gsm_off() started
gsm_off() finished
gsm_on(): try again
4
gsm_send_at() started
gsm_send_at() completed
0
gsm_on(): failed auto-baudrate
Warning: timed out waiting for last modem reply
Reply failure count:
1
Warning: timed out waiting for last modem reply
Reply failure count:
2
gsm_on() finished
gsm_set_pin() started
Warning: timed out waiting for last modem reply
Reply failure count:
3
Warning: timed out waiting for last modem reply
Reply failure count:
4
Warning: timed out waiting for last modem reply
Reply failure count:
5
Warning: timed out waiting for last modem reply
Reply failure count:
6
Warning: timed out waiting for last modem reply
Reply failure count:
7
gsm_set_pin() completed
gsm_get_modem_status() started
Warning: timed out waiting for last modem reply
Reply failure count:
8
gsm_get_modem_status() returned: 
-1
gsm_get_modem_status() started
Warning: timed out waiting for last modem reply
Reply failure count:
9
gsm_get_modem_status() returned: 
-1
gsm_get_modem_status() started
Warning: timed out waiting for last modem reply
Reply failure count:
10
reboot() started
gps_off() started
gps_off() completed
gsm_off() started

The OpenTracker will loop this constantly..

gsm.ino "gsm_send_at()" looks following now:

int gsm_send_at() {
  debug_print(F("gsm_send_at() started"));

  int ret = 0;
  for (int k=0; k<5; ++k) {
    gsm_port.print("ATE1\r");
    status_delay(50);

    gsm_get_reply(1);
    ret = (strstr(modem_reply, "ATE1") != NULL)
      && (strstr(modem_reply, "OK") != NULL);
    if (ret) break;

    status_delay(1000);
  }
  debug_print(F("gsm_send_at() completed"));
  debug_print(ret);
  return ret;
}

Any more ideas how to solve this issue? Could there be some setting in modem which could be resetted somehow?

Do you have any similar HW rev 2.4C boards available there to test the same? Could this same issue be repeated(?).

Hope you could reply soon. Thank you in advance.

ppescher commented 7 years ago

The RDY message is a kind of "URC" (unsolicited result code) which is sent by the modem to notify about particular events (in this case the modem is ready to accept commands). The problem is that the modem appears to be "ready" (RDY) after all attempts to receive a reply.

Try to #define DEBUG 10 in your Tracker.h That will start a debug terminal after modem initialization (which will fail after 1 minute in your case) and you will be able to manually send AT commands to the modem. Things you can try to type: AT ATI ATE1 Until you see an echo of what you type on the serial monitor, just before the modem reply.

If you can get sensible replies from the modem and enable the echo, then it might be a timing issue. The code does not wait long enough for the modem to become ready and start replying normally. In that case it should be enough to modify gsm_send_at() to retry 10 times for example, instead of 5 (every attempt takes roughly 1 second).

Codematic commented 7 years ago

Well, thank you once again for your support. The initial issue were not to define MODEM_UG96 at all in tracker.h. After that, I got it working somehow, but still connecting to server is not working. It seems to be right here.

The key error message is +CEER: "No report available" as shown below.

Data accumulated:
4
gsm_send_at() started
Modem Reply:
ATE1

OK

gsm_send_at() completed
1
gsm_disconnect() started
Modem Line:
AT+QICLOSE=0

Modem Line:
OK

gsm_disconnect() completed
gsm_connect() started
gsm_get_modem_status() started
Modem Reply:
AT+CPAS

Modem Reply:
+CPAS: 0

Modem Line:

Modem Line:
OK

gsm_get_modem_status() returned: 
0
gsm_get_connection_status() started
Modem Line:
AT+QISTATE=1,0

Modem Line:
OK

Modem Line:
AT+CGACT?

Modem Line:
+CGACT: 1,0

Modem Line:

Modem Line:
OK

Modem Reply:
AT+CGACT?

+CGACT: 1,0

OK

gsm_get_connection_status() returned:
-2
Modem Line:
AT+QIDEACT=1

Modem Line:
OK

Modem Line:
AT+QIACT=1

Modem Line:

Modem Line:
OK

Modem Line:
AT+QIDNSCFG=1,"8.8.8.8"

Modem Line:
OK

Connecting to remote server...
0
Modem Line:
AT+QIOPEN=1,0,"TCP","updates.geolink.io","80"

Modem Line:
ERROR

Can not connect to remote server: 
updates.geolink.io
Modem Line:
AT+CEER

Modem Line:
+CEER: "No report available"

Modem Line:

Modem Line:
OK

gsm_get_modem_status() started
Modem Reply:
AT+CPAS

Modem Reply:
+CPAS: 0

Modem Line:

Modem Line:
OK

In gsm.ino it is about this function :

int gsm_connect() {
  int ret = 0;

  debug_print(F("gsm_connect() started"));

  //try to connect multiple times
  for(int i=0;i<CONNECT_RETRY;i++) {
    // connect only when modem is ready
    if (gsm_get_modem_status() == 0) {
      // check if connected from previous attempts
      int ipstat = gsm_get_connection_status();  

      if (ipstat > 1) {
        //close connection, if previous attempts failed
        gsm_port.print(AT_CLOSE);
        gsm_wait_for_reply(MODEM_UG96,0);
        ipstat = 0;
      }
      if (ipstat < 0) {
        //deactivate required
        gsm_port.print(AT_DEACTIVATE);
        gsm_wait_for_reply(MODEM_UG96,0);
        ipstat = 0;

#if MODEM_UG96
        gsm_port.print(AT_ACTIVATE);
        gsm_wait_for_reply(1,0);

        gsm_port.print(AT_CONFIGDNS "\"8.8.8.8\"");
        gsm_port.print("\r");

        gsm_wait_for_reply(1,0);
#endif
      }
      if (ipstat == 0) {
        debug_print(F("Connecting to remote server..."));
        debug_print(i);

        //open socket connection to remote host
        //opening connection
        gsm_port.print(AT_OPEN "\"");
        gsm_port.print(PROTO);
        gsm_port.print("\",\"");
        gsm_port.print(HOSTNAME);
        gsm_port.print("\",");
#if MODEM_M95
        gsm_port.print("\"");
#endif
        gsm_port.print(HTTP_PORT);
#if MODEM_M95
        gsm_port.print("\"");
#endif
        gsm_port.print("\r");

        gsm_wait_for_reply(1, 0); // OK sent first

        long timer = millis();
        if(strstr(modem_reply, "OK")==NULL)
          ipstat = 0;
        else
        do {
          gsm_get_reply(1);

#if MODEM_UG96
          char *tmp = strstr(modem_reply, "+QIOPEN: 0,");
          if(tmp!=NULL) {
            tmp += strlen("+QIOPEN: 0,");
            if (atoi(tmp)==0)
              ipstat = 1;
            else
              ipstat = 0;
            break;
          }
#else
          if(strstr(modem_reply, "CONNECT OK")!=NULL) {
            ipstat = 1;
            break;
          }
          if(strstr(modem_reply, "CONNECT FAIL")!=NULL ||
            strstr(modem_reply, "ERROR")!=NULL) {
            ipstat = 0;
            break;
          }
#endif
          addon_delay(100);
        } while (millis() - timer < CONNECT_TIMEOUT);
      }

      if(ipstat == 1) {
        debug_print(F("Connected to remote server: "));
        debug_print(HOSTNAME);

        ret = 1;
        break;
      } else {
        debug_print(F("Can not connect to remote server: "));
        debug_print(HOSTNAME);
        // debug only:
        gsm_port.print("AT+CEER\r");
        gsm_wait_for_reply(1,0);
      }
    }

    addon_delay(2000); // wait 2s before retrying
  }
  debug_print(F("gsm_connect() completed"));
  return ret;
}

Any ideas what to test next?

Btw, with the #define DEBUG 10 the code did not reached the testing phase at all since the MODEM_96 were not defined (it just rebooted earlier).

Thanks.

ppescher commented 7 years ago

Ok, you don't have to define MODEM_UG96 manually. It is defined automatically when you select the correct board hardware in the Arduino IDE: in the menu Tools > Board Version you should set "OpenTracker 2.5 (3G)" (the board revision number is a mistake, it's ok for 2.4C and will be corrected in the next release).

Please make sure you have configured the APN correctly for your SIM card. I don't see the initial diagnostic messages in your log.

Codematic commented 7 years ago

Finally I got it working.

I added these two lines into the gsm.ino : image

Got error stating: +QIGETERROR: 552, invalid parameters

The real pain were these preprocessor IF-statements: image

UG96 does not like parenthesis around the port number.

Summary to solve this issue with UG96 modem were just to define those two preprocessor parameters to the tracker.h:

#define MODEM_M95 0
#define MODEM_UG96 1

Just noted Paolo's last reply...

Tested the board definition and yes indeed, it will clear the same.

Hmm, such a small issue (the board number 2.5 vs. 2.4C) but causes many hour of investigation.

Anyway Paolo, thank you for your constant and prompt support. I will close this for now.

ppescher commented 7 years ago

FYI - I've just released board support package v1.0.5 (you can get it via Arduino IDE Board Manager) and firmware package v3.2.0

I know this comes just a bit too late for you and I'm sorry for the inconvenience. Our release policy so far has been to follow our board production schedule, unless immediate action to fix serious bugs is deemed necessary. This time we had some delay due to summer closing. Thanks for understanding.